diff --git a/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java b/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
index b0ac27aef53..261a7f7e073 100644
--- a/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
+++ b/cscore/src/main/java/edu/wpi/first/cscore/CameraServerJNI.java
@@ -1025,10 +1025,10 @@ public interface LoggerFunction {
/**
* Runs main run loop with timeout.
*
- * @param timeoutSeconds Timeout in seconds.
+ * @param timeout Timeout in seconds.
* @return 3 on timeout, 2 on signal, 1 on other.
*/
- public static native int runMainRunLoopTimeout(double timeoutSeconds);
+ public static native int runMainRunLoopTimeout(double timeout);
/** Stops main run loop. */
public static native void stopMainRunLoop();
diff --git a/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java b/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
index 77eebf014ff..74ea535c61f 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
@@ -47,10 +47,10 @@ public class DMAJNI extends JNIWrapper {
*
This can only be called if DMA is not started.
*
* @param handle the dma handle
- * @param periodSeconds the period to trigger in seconds
+ * @param period the period to trigger in seconds
* @see "HAL_SetDMATimedTrigger"
*/
- public static native void setTimedTrigger(int handle, double periodSeconds);
+ public static native void setTimedTrigger(int handle, double period);
/**
* Sets DMA transfers to occur at a specific timed interval in FPGA cycles.
@@ -229,14 +229,13 @@ public static native int setExternalTrigger(
* Reads a DMA sample from the queue.
*
* @param handle the dma handle
- * @param timeoutSeconds the time to wait for data to be queued before timing out
+ * @param timeout the time in seconds to wait for data to be queued before timing out
* @param buffer the sample object to place data into
* @param sampleStore index 0-21 channelOffsets, index 22: capture size, index 23: triggerChannels
* (bitflags), index 24: remaining, index 25: read status
* @return timestamp of the DMA Sample
*/
- public static native long readDMA(
- int handle, double timeoutSeconds, int[] buffer, int[] sampleStore);
+ public static native long readDMA(int handle, double timeout, int[] buffer, int[] sampleStore);
/**
* Get the sensor DMA sample.
diff --git a/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java b/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
index df66c558b0c..e4c83773090 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
@@ -29,8 +29,8 @@ static class BaseStore {
/** Default constructor. */
public DMAJNISample() {}
- public int update(int dmaHandle, double timeoutSeconds) {
- m_timeStamp = DMAJNI.readDMA(dmaHandle, timeoutSeconds, m_dataBuffer, m_storage);
+ public int update(int dmaHandle, double timeout) {
+ m_timeStamp = DMAJNI.readDMA(dmaHandle, timeout, m_dataBuffer, m_storage);
return m_storage[25];
}
diff --git a/sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h b/sysid/src/main/native/include/sysid/analysis/TrackwidthAnalysis.h
similarity index 84%
rename from sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h
rename to sysid/src/main/native/include/sysid/analysis/TrackwidthAnalysis.h
index d086022bff1..ecc319a180a 100644
--- a/sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h
+++ b/sysid/src/main/native/include/sysid/analysis/TrackwidthAnalysis.h
@@ -10,14 +10,14 @@
namespace sysid {
/**
- * Calculates the track width given the left distance, right distance, and
+ * Calculates the trackwidth given the left distance, right distance, and
* accumulated gyro angle.
*
* @param l The distance traveled by the left side of the drivetrain.
* @param r The distance traveled by the right side of the drivetrain.
* @param accum The accumulated gyro angle.
*/
-constexpr double CalculateTrackWidth(double l, double r,
+constexpr double CalculateTrackwidth(double l, double r,
units::radian_t accum) {
// The below comes from solving ω = (vr − vl) / 2r for 2r.
return (gcem::abs(r) + gcem::abs(l)) / gcem::abs(accum.value());
diff --git a/sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp b/sysid/src/test/native/cpp/analysis/TrackwidthAnalysisTest.cpp
similarity index 64%
rename from sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp
rename to sysid/src/test/native/cpp/analysis/TrackwidthAnalysisTest.cpp
index e7b662fe9d0..d5e2dc16675 100644
--- a/sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp
+++ b/sysid/src/test/native/cpp/analysis/TrackwidthAnalysisTest.cpp
@@ -4,9 +4,9 @@
#include
-#include "sysid/analysis/TrackWidthAnalysis.h"
+#include "sysid/analysis/TrackwidthAnalysis.h"
-TEST(TrackWidthAnalysisTest, Calculate) {
- double result = sysid::CalculateTrackWidth(-0.5386, 0.5386, 90_deg);
+TEST(TrackwidthAnalysisTest, Calculate) {
+ double result = sysid::CalculateTrackwidth(-0.5386, 0.5386, 90_deg);
EXPECT_NEAR(result, 0.6858, 1E-4);
}
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
index 440018817c2..b93cfa40938 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java
@@ -47,7 +47,7 @@ public class MecanumControllerCommand extends Command {
private final MecanumDriveKinematics m_kinematics;
private final HolonomicDriveController m_controller;
private final Supplier m_desiredRotation;
- private final double m_maxWheelVelocityMetersPerSecond;
+ private final double m_maxWheelVelocity;
private final PIDController m_frontLeftController;
private final PIDController m_rearLeftController;
private final PIDController m_frontRightController;
@@ -78,7 +78,7 @@ public class MecanumControllerCommand extends Command {
* @param thetaController The Trajectory Tracker PID controller for angle for the robot.
* @param desiredRotation The angle that the robot should be facing. This is sampled at each time
* step.
- * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param maxWheelVelocity The maximum velocity of a drivetrain wheel in m/s.
* @param frontLeftController The front left wheel velocity PID.
* @param rearLeftController The rear left wheel velocity PID.
* @param frontRightController The front right wheel velocity PID.
@@ -98,7 +98,7 @@ public MecanumControllerCommand(
PIDController yController,
ProfiledPIDController thetaController,
Supplier desiredRotation,
- double maxWheelVelocityMetersPerSecond,
+ double maxWheelVelocity,
PIDController frontLeftController,
PIDController rearLeftController,
PIDController frontRightController,
@@ -120,7 +120,7 @@ public MecanumControllerCommand(
m_desiredRotation =
requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");
- m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
+ m_maxWheelVelocity = maxWheelVelocity;
m_frontLeftController =
requireNonNullParam(frontLeftController, "frontLeftController", "MecanumControllerCommand");
@@ -166,7 +166,7 @@ public MecanumControllerCommand(
* @param xController The Trajectory Tracker PID controller for the robot's x position.
* @param yController The Trajectory Tracker PID controller for the robot's y position.
* @param thetaController The Trajectory Tracker PID controller for angle for the robot.
- * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param maxWheelVelocity The maximum velocity of a drivetrain wheel in m/s.
* @param frontLeftController The front left wheel velocity PID.
* @param rearLeftController The rear left wheel velocity PID.
* @param frontRightController The front right wheel velocity PID.
@@ -184,7 +184,7 @@ public MecanumControllerCommand(
PIDController xController,
PIDController yController,
ProfiledPIDController thetaController,
- double maxWheelVelocityMetersPerSecond,
+ double maxWheelVelocity,
PIDController frontLeftController,
PIDController rearLeftController,
PIDController frontRightController,
@@ -200,9 +200,8 @@ public MecanumControllerCommand(
xController,
yController,
thetaController,
- () ->
- trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
- maxWheelVelocityMetersPerSecond,
+ () -> trajectory.getStates().get(trajectory.getStates().size() - 1).pose.getRotation(),
+ maxWheelVelocity,
frontLeftController,
rearLeftController,
frontRightController,
@@ -228,7 +227,7 @@ public MecanumControllerCommand(
* @param thetaController The Trajectory Tracker PID controller for angle for the robot.
* @param desiredRotation The angle that the robot should be facing. This is sampled at each time
* step.
- * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param maxWheelVelocity The maximum velocity of a drivetrain wheel in m/s.
* @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
* @param requirements The subsystems to require.
*/
@@ -241,7 +240,7 @@ public MecanumControllerCommand(
PIDController yController,
ProfiledPIDController thetaController,
Supplier desiredRotation,
- double maxWheelVelocityMetersPerSecond,
+ double maxWheelVelocity,
Consumer outputWheelSpeeds,
Subsystem... requirements) {
m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand");
@@ -258,7 +257,7 @@ public MecanumControllerCommand(
m_desiredRotation =
requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");
- m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
+ m_maxWheelVelocity = maxWheelVelocity;
m_frontLeftController = null;
m_rearLeftController = null;
@@ -296,7 +295,7 @@ public MecanumControllerCommand(
* @param xController The Trajectory Tracker PID controller for the robot's x position.
* @param yController The Trajectory Tracker PID controller for the robot's y position.
* @param thetaController The Trajectory Tracker PID controller for angle for the robot.
- * @param maxWheelVelocityMetersPerSecond The maximum velocity of a drivetrain wheel.
+ * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
* @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
* @param requirements The subsystems to require.
*/
@@ -307,7 +306,7 @@ public MecanumControllerCommand(
PIDController xController,
PIDController yController,
ProfiledPIDController thetaController,
- double maxWheelVelocityMetersPerSecond,
+ double maxWheelVelocity,
Consumer outputWheelSpeeds,
Subsystem... requirements) {
this(
@@ -317,9 +316,8 @@ public MecanumControllerCommand(
xController,
yController,
thetaController,
- () ->
- trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
- maxWheelVelocityMetersPerSecond,
+ () -> trajectory.getStates().get(trajectory.getStates().size() - 1).pose.getRotation(),
+ maxWheelVelocity,
outputWheelSpeeds,
requirements);
}
@@ -328,18 +326,16 @@ public MecanumControllerCommand(
public void initialize() {
var initialState = m_trajectory.sample(0);
- var initialXVelocity =
- initialState.velocityMetersPerSecond * initialState.poseMeters.getRotation().getCos();
- var initialYVelocity =
- initialState.velocityMetersPerSecond * initialState.poseMeters.getRotation().getSin();
+ var initialXVelocity = initialState.velocity * initialState.pose.getRotation().getCos();
+ var initialYVelocity = initialState.velocity * initialState.pose.getRotation().getSin();
MecanumDriveWheelSpeeds prevSpeeds =
m_kinematics.toWheelSpeeds(new ChassisSpeeds(initialXVelocity, initialYVelocity, 0.0));
- m_prevFrontLeftSpeedSetpoint = prevSpeeds.frontLeftMetersPerSecond;
- m_prevRearLeftSpeedSetpoint = prevSpeeds.rearLeftMetersPerSecond;
- m_prevFrontRightSpeedSetpoint = prevSpeeds.frontRightMetersPerSecond;
- m_prevRearRightSpeedSetpoint = prevSpeeds.rearRightMetersPerSecond;
+ m_prevFrontLeftSpeedSetpoint = prevSpeeds.frontLeft;
+ m_prevRearLeftSpeedSetpoint = prevSpeeds.rearLeft;
+ m_prevFrontRightSpeedSetpoint = prevSpeeds.frontRight;
+ m_prevRearRightSpeedSetpoint = prevSpeeds.rearRight;
m_timer.restart();
}
@@ -354,12 +350,12 @@ public void execute() {
m_controller.calculate(m_pose.get(), desiredState, m_desiredRotation.get());
var targetWheelSpeeds = m_kinematics.toWheelSpeeds(targetChassisSpeeds);
- targetWheelSpeeds.desaturate(m_maxWheelVelocityMetersPerSecond);
+ targetWheelSpeeds.desaturate(m_maxWheelVelocity);
- double frontLeftSpeedSetpoint = targetWheelSpeeds.frontLeftMetersPerSecond;
- double rearLeftSpeedSetpoint = targetWheelSpeeds.rearLeftMetersPerSecond;
- double frontRightSpeedSetpoint = targetWheelSpeeds.frontRightMetersPerSecond;
- double rearRightSpeedSetpoint = targetWheelSpeeds.rearRightMetersPerSecond;
+ double frontLeftSpeedSetpoint = targetWheelSpeeds.frontLeft;
+ double rearLeftSpeedSetpoint = targetWheelSpeeds.rearLeft;
+ double frontRightSpeedSetpoint = targetWheelSpeeds.frontRight;
+ double rearRightSpeedSetpoint = targetWheelSpeeds.rearRight;
double frontLeftOutput;
double rearLeftOutput;
@@ -382,22 +378,22 @@ public void execute() {
frontLeftOutput =
frontLeftFeedforward
+ m_frontLeftController.calculate(
- m_currentWheelSpeeds.get().frontLeftMetersPerSecond, frontLeftSpeedSetpoint);
+ m_currentWheelSpeeds.get().frontLeft, frontLeftSpeedSetpoint);
rearLeftOutput =
rearLeftFeedforward
+ m_rearLeftController.calculate(
- m_currentWheelSpeeds.get().rearLeftMetersPerSecond, rearLeftSpeedSetpoint);
+ m_currentWheelSpeeds.get().rearLeft, rearLeftSpeedSetpoint);
frontRightOutput =
frontRightFeedforward
+ m_frontRightController.calculate(
- m_currentWheelSpeeds.get().frontRightMetersPerSecond, frontRightSpeedSetpoint);
+ m_currentWheelSpeeds.get().frontRight, frontRightSpeedSetpoint);
rearRightOutput =
rearRightFeedforward
+ m_rearRightController.calculate(
- m_currentWheelSpeeds.get().rearRightMetersPerSecond, rearRightSpeedSetpoint);
+ m_currentWheelSpeeds.get().rearRight, rearRightSpeedSetpoint);
m_outputDriveVoltages.accept(
new MecanumDriveMotorVoltages(
@@ -420,6 +416,6 @@ public void end(boolean interrupted) {
@Override
public boolean isFinished() {
- return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
+ return m_timer.hasElapsed(m_trajectory.getTotalTime());
}
}
diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
index 424a288b03b..06d63ebb2e1 100644
--- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
+++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java
@@ -123,8 +123,7 @@ public SwerveControllerCommand(
xController,
yController,
thetaController,
- () ->
- trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
+ () -> trajectory.getStates().get(trajectory.getStates().size() - 1).pose.getRotation(),
outputModuleStates,
requirements);
}
@@ -162,8 +161,7 @@ public SwerveControllerCommand(
pose,
kinematics,
controller,
- () ->
- trajectory.getStates().get(trajectory.getStates().size() - 1).poseMeters.getRotation(),
+ () -> trajectory.getStates().get(trajectory.getStates().size() - 1).pose.getRotation(),
outputModuleStates,
requirements);
}
@@ -233,6 +231,6 @@ public void end(boolean interrupted) {
@Override
public boolean isFinished() {
- return m_timer.hasElapsed(m_trajectory.getTotalTimeSeconds());
+ return m_timer.hasElapsed(m_trajectory.getTotalTime());
}
}
diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
index 9ac412ce50b..5f5f3731f5e 100644
--- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
+++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java
@@ -60,24 +60,24 @@ void cleanupAll() {
private static final double kAngularTolerance = 1 / 12.0;
private static final double kWheelBase = 0.5;
- private static final double kTrackWidth = 0.5;
+ private static final double kTrackwidth = 0.5;
private final MecanumDriveKinematics m_kinematics =
new MecanumDriveKinematics(
- new Translation2d(kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
+ new Translation2d(kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(kWheelBase / 2, -kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, -kTrackwidth / 2));
private final MecanumDriveOdometry m_odometry =
new MecanumDriveOdometry(
m_kinematics, Rotation2d.kZero, new MecanumDriveWheelPositions(), Pose2d.kZero);
public void setWheelSpeeds(MecanumDriveWheelSpeeds wheelSpeeds) {
- this.m_frontLeftSpeed = wheelSpeeds.frontLeftMetersPerSecond;
- this.m_rearLeftSpeed = wheelSpeeds.rearLeftMetersPerSecond;
- this.m_frontRightSpeed = wheelSpeeds.frontRightMetersPerSecond;
- this.m_rearRightSpeed = wheelSpeeds.rearRightMetersPerSecond;
+ this.m_frontLeftSpeed = wheelSpeeds.frontLeft;
+ this.m_rearLeftSpeed = wheelSpeeds.rearLeft;
+ this.m_frontRightSpeed = wheelSpeeds.frontRight;
+ this.m_rearRightSpeed = wheelSpeeds.rearRight;
}
public MecanumDriveWheelPositions getCurrentWheelDistances() {
@@ -87,7 +87,7 @@ public MecanumDriveWheelPositions getCurrentWheelDistances() {
public Pose2d getRobotPose() {
m_odometry.update(m_angle, getCurrentWheelDistances());
- return m_odometry.getPoseMeters();
+ return m_odometry.getPose();
}
@Test
@@ -101,7 +101,7 @@ void testReachesReference() {
var config = new TrajectoryConfig(8.8, 0.1);
final var trajectory = TrajectoryGenerator.generateTrajectory(waypoints, config);
- final var endState = trajectory.sample(trajectory.getTotalTimeSeconds());
+ final var endState = trajectory.sample(trajectory.getTotalTime());
final var command =
new MecanumControllerCommand(
@@ -120,7 +120,7 @@ void testReachesReference() {
command.initialize();
while (!command.isFinished()) {
command.execute();
- m_angle = trajectory.sample(m_timer.get()).poseMeters.getRotation();
+ m_angle = trajectory.sample(m_timer.get()).pose.getRotation();
m_frontLeftDistance += m_frontLeftSpeed * 0.005;
m_rearLeftDistance += m_rearLeftSpeed * 0.005;
m_frontRightDistance += m_frontRightSpeed * 0.005;
@@ -131,11 +131,11 @@ void testReachesReference() {
command.end(true);
assertAll(
- () -> assertEquals(endState.poseMeters.getX(), getRobotPose().getX(), kxTolerance),
- () -> assertEquals(endState.poseMeters.getY(), getRobotPose().getY(), kyTolerance),
+ () -> assertEquals(endState.pose.getX(), getRobotPose().getX(), kxTolerance),
+ () -> assertEquals(endState.pose.getY(), getRobotPose().getY(), kyTolerance),
() ->
assertEquals(
- endState.poseMeters.getRotation().getRadians(),
+ endState.pose.getRotation().getRadians(),
getRobotPose().getRotation().getRadians(),
kAngularTolerance));
}
diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
index 0abe4990486..2d91497f347 100644
--- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
+++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java
@@ -67,14 +67,14 @@ void cleanup() {
private static final double kAngularTolerance = 1 / 12.0;
private static final double kWheelBase = 0.5;
- private static final double kTrackWidth = 0.5;
+ private static final double kTrackwidth = 0.5;
private final SwerveDriveKinematics m_kinematics =
new SwerveDriveKinematics(
- new Translation2d(kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
+ new Translation2d(kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(kWheelBase / 2, -kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, -kTrackwidth / 2));
private final SwerveDriveOdometry m_odometry =
new SwerveDriveOdometry(m_kinematics, Rotation2d.kZero, m_modulePositions, Pose2d.kZero);
@@ -86,7 +86,7 @@ public void setModuleStates(SwerveModuleState[] moduleStates) {
public Pose2d getRobotPose() {
m_odometry.update(m_angle, m_modulePositions);
- return m_odometry.getPoseMeters();
+ return m_odometry.getPose();
}
@Test
@@ -100,7 +100,7 @@ void testReachesReference() {
var config = new TrajectoryConfig(8.8, 0.1);
final var trajectory = TrajectoryGenerator.generateTrajectory(waypoints, config);
- final var endState = trajectory.sample(trajectory.getTotalTimeSeconds());
+ final var endState = trajectory.sample(trajectory.getTotalTime());
final var command =
new SwerveControllerCommand(
@@ -118,10 +118,10 @@ void testReachesReference() {
command.initialize();
while (!command.isFinished()) {
command.execute();
- m_angle = trajectory.sample(m_timer.get()).poseMeters.getRotation();
+ m_angle = trajectory.sample(m_timer.get()).pose.getRotation();
for (int i = 0; i < m_modulePositions.length; i++) {
- m_modulePositions[i].distanceMeters += m_moduleStates[i].speedMetersPerSecond * 0.005;
+ m_modulePositions[i].distance += m_moduleStates[i].speed * 0.005;
m_modulePositions[i].angle = m_moduleStates[i].angle;
}
@@ -131,11 +131,11 @@ void testReachesReference() {
command.end(true);
assertAll(
- () -> assertEquals(endState.poseMeters.getX(), getRobotPose().getX(), kxTolerance),
- () -> assertEquals(endState.poseMeters.getY(), getRobotPose().getY(), kyTolerance),
+ () -> assertEquals(endState.pose.getX(), getRobotPose().getX(), kxTolerance),
+ () -> assertEquals(endState.pose.getY(), getRobotPose().getY(), kyTolerance),
() ->
assertEquals(
- endState.poseMeters.getRotation().getRadians(),
+ endState.pose.getRotation().getRadians(),
getRobotPose().getRotation().getRadians(),
kAngularTolerance));
}
diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
index c79432d99eb..04af56a682d 100644
--- a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
+++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp
@@ -51,13 +51,13 @@ class MecanumControllerCommandTest : public ::testing::Test {
static constexpr units::radian_t kAngularTolerance{1 / 12.0};
static constexpr units::meter_t kWheelBase{0.5};
- static constexpr units::meter_t kTrackWidth{0.5};
+ static constexpr units::meter_t kTrackwidth{0.5};
frc::MecanumDriveKinematics m_kinematics{
- frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
+ frc::Translation2d{kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{kWheelBase / 2, -kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, -kTrackwidth / 2}};
frc::MecanumDriveOdometry m_odometry{m_kinematics, 0_rad,
getCurrentWheelDistances(),
diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
index b96a1e1c139..82036514e45 100644
--- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
+++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp
@@ -51,13 +51,13 @@ class SwerveControllerCommandTest : public ::testing::Test {
static constexpr units::radian_t kAngularTolerance{1 / 12.0};
static constexpr units::meter_t kWheelBase{0.5};
- static constexpr units::meter_t kTrackWidth{0.5};
+ static constexpr units::meter_t kTrackwidth{0.5};
frc::SwerveDriveKinematics<4> m_kinematics{
- frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
+ frc::Translation2d{kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{kWheelBase / 2, -kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, -kTrackwidth / 2}};
frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, 0_rad, m_modulePositions,
frc::Pose2d{0_m, 0_m, 0_rad}};
diff --git a/wpilibc/src/main/native/cpp/SharpIR.cpp b/wpilibc/src/main/native/cpp/SharpIR.cpp
index 67e00f6a67e..3be2d777165 100644
--- a/wpilibc/src/main/native/cpp/SharpIR.cpp
+++ b/wpilibc/src/main/native/cpp/SharpIR.cpp
@@ -6,6 +6,7 @@
#include
+#include
#include
#include
@@ -14,28 +15,29 @@
using namespace frc;
SharpIR SharpIR::GP2Y0A02YK0F(int channel) {
- return SharpIR(channel, 62.28, -1.092, 20, 150.0);
+ return SharpIR(channel, 62.28, -1.092, 20_cm, 150_cm);
}
SharpIR SharpIR::GP2Y0A21YK0F(int channel) {
- return SharpIR(channel, 26.449, -1.226, 10.0, 80.0);
+ return SharpIR(channel, 26.449, -1.226, 10_cm, 80_cm);
}
SharpIR SharpIR::GP2Y0A41SK0F(int channel) {
- return SharpIR(channel, 12.354, -1.07, 4.0, 30.0);
+ return SharpIR(channel, 12.354, -1.07, 4_cm, 30_cm);
}
SharpIR SharpIR::GP2Y0A51SK0F(int channel) {
- return SharpIR(channel, 5.2819, -1.161, 2.0, 15.0);
+ return SharpIR(channel, 5.2819, -1.161, 2_cm, 15_cm);
}
-SharpIR::SharpIR(int channel, double a, double b, double minCM, double maxCM)
- : m_sensor(channel), m_A(a), m_B(b), m_minCM(minCM), m_maxCM(maxCM) {
+SharpIR::SharpIR(int channel, double a, double b, units::meter_t min,
+ units::meter_t max)
+ : m_sensor(channel), m_A(a), m_B(b), m_min(min), m_max(max) {
wpi::SendableRegistry::AddLW(this, "SharpIR", channel);
m_simDevice = hal::SimDevice("SharpIR", m_sensor.GetChannel());
if (m_simDevice) {
- m_simRange = m_simDevice.CreateDouble("Range (cm)", false, 0.0);
+ m_simRange = m_simDevice.CreateDouble("Range (m)", false, 0.0);
m_sensor.SetSimDevice(m_simDevice);
}
}
@@ -44,19 +46,16 @@ int SharpIR::GetChannel() const {
return m_sensor.GetChannel();
}
-units::centimeter_t SharpIR::GetRange() const {
- double distance;
-
+units::meter_t SharpIR::GetRange() const {
if (m_simRange) {
- distance = m_simRange.Get();
+ return std::clamp(units::meter_t{m_simRange.Get()}, m_min, m_max);
} else {
// Don't allow zero/negative values
auto v = std::max(m_sensor.GetVoltage(), 0.00001);
- distance = m_A * std::pow(v, m_B);
- }
- // Always constrain output
- return units::centimeter_t{std::max(std::min(distance, m_maxCM), m_minCM)};
+ return std::clamp(units::meter_t{m_A * std::pow(v, m_B) * 1e-2}, m_min,
+ m_max);
+ }
}
void SharpIR::InitSendable(wpi::SendableBuilder& builder) {
diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp
index 640a56c4f41..edb566621e7 100644
--- a/wpilibc/src/main/native/cpp/Ultrasonic.cpp
+++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp
@@ -137,7 +137,7 @@ void Ultrasonic::SetAutomaticMode(bool enabling) {
units::meter_t Ultrasonic::GetRange() const {
if (IsRangeValid()) {
if (m_simRange) {
- return units::inch_t{m_simRange.Get()};
+ return units::meter_t{m_simRange.Get()};
}
return m_counter.GetPeriod() * kSpeedOfSound / 2.0;
} else {
@@ -164,7 +164,7 @@ void Ultrasonic::Initialize() {
m_simDevice = hal::SimDevice("Ultrasonic", m_echoChannel->GetChannel());
if (m_simDevice) {
m_simRangeValid = m_simDevice.CreateBoolean("Range Valid", false, true);
- m_simRange = m_simDevice.CreateDouble("Range (in)", false, 0.0);
+ m_simRange = m_simDevice.CreateDouble("Range (m)", false, 0.0);
m_pingChannel->SetSimDevice(m_simDevice);
m_echoChannel->SetSimDevice(m_simDevice);
}
diff --git a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
index 19f3ab6c7d3..b61b6ad6c9d 100644
--- a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
@@ -18,11 +18,11 @@ using namespace frc;
using namespace frc::sim;
DifferentialDrivetrainSim::DifferentialDrivetrainSim(
- LinearSystem<2, 2, 2> plant, units::meter_t trackWidth, DCMotor driveMotor,
+ LinearSystem<2, 2, 2> plant, units::meter_t trackwidth, DCMotor driveMotor,
double gearRatio, units::meter_t wheelRadius,
const std::array& measurementStdDevs)
: m_plant(std::move(plant)),
- m_rb(trackWidth / 2.0),
+ m_rb(trackwidth / 2.0),
m_wheelRadius(wheelRadius),
m_motor(driveMotor),
m_originalGearing(gearRatio),
@@ -36,11 +36,11 @@ DifferentialDrivetrainSim::DifferentialDrivetrainSim(
DifferentialDrivetrainSim::DifferentialDrivetrainSim(
frc::DCMotor driveMotor, double gearing, units::kilogram_square_meter_t J,
units::kilogram_t mass, units::meter_t wheelRadius,
- units::meter_t trackWidth, const std::array& measurementStdDevs)
+ units::meter_t trackwidth, const std::array& measurementStdDevs)
: DifferentialDrivetrainSim(
frc::LinearSystemId::DrivetrainVelocitySystem(
- driveMotor, mass, wheelRadius, trackWidth / 2.0, J, gearing),
- trackWidth, driveMotor, gearing, wheelRadius, measurementStdDevs) {}
+ driveMotor, mass, wheelRadius, trackwidth / 2.0, J, gearing),
+ trackwidth, driveMotor, gearing, wheelRadius, measurementStdDevs) {}
Eigen::Vector2d DifferentialDrivetrainSim::ClampInput(
const Eigen::Vector2d& u) {
diff --git a/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp b/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp
index 46922aa6e4a..d5abf6cc423 100644
--- a/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp
@@ -16,9 +16,9 @@ SharpIRSim::SharpIRSim(const SharpIR& sharpIR)
SharpIRSim::SharpIRSim(int channel) {
frc::sim::SimDeviceSim deviceSim{"SharpIR", channel};
- m_simRange = deviceSim.GetDouble("Range (cm)");
+ m_simRange = deviceSim.GetDouble("Range (m)");
}
-void SharpIRSim::SetRange(units::centimeter_t rng) {
- m_simRange.Set(rng.value());
+void SharpIRSim::SetRange(units::meter_t range) {
+ m_simRange.Set(range.value());
}
diff --git a/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp b/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
index 1016c4bccbc..56af35fc403 100644
--- a/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
@@ -15,13 +15,13 @@ UltrasonicSim::UltrasonicSim(const frc::Ultrasonic& ultrasonic)
UltrasonicSim::UltrasonicSim(int ping, int echo) {
frc::sim::SimDeviceSim deviceSim{"Ultrasonic", echo};
m_simRangeValid = deviceSim.GetBoolean("Range Valid");
- m_simRange = deviceSim.GetDouble("Range (in)");
+ m_simRange = deviceSim.GetDouble("Range (m)");
}
void UltrasonicSim::SetRangeValid(bool valid) {
m_simRangeValid.Set(valid);
}
-void UltrasonicSim::SetRange(units::inch_t range) {
+void UltrasonicSim::SetRange(units::meter_t range) {
m_simRange.Set(range.value());
}
diff --git a/wpilibc/src/main/native/include/frc/SharpIR.h b/wpilibc/src/main/native/include/frc/SharpIR.h
index 4dd7e433192..df637a4dd99 100644
--- a/wpilibc/src/main/native/include/frc/SharpIR.h
+++ b/wpilibc/src/main/native/include/frc/SharpIR.h
@@ -63,10 +63,11 @@ class SharpIR : public wpi::Sendable, public wpi::SendableHelper {
* @param channel Analog input channel the sensor is connected to
* @param a Constant A
* @param b Constant B
- * @param minCM Minimum distance to report in centimeters
- * @param maxCM Maximum distance to report in centimeters
+ * @param min Minimum distance to report
+ * @param max Maximum distance to report
*/
- SharpIR(int channel, double a, double b, double minCM, double maxCM);
+ SharpIR(int channel, double a, double b, units::meter_t min,
+ units::meter_t max);
/**
* Get the analog input channel number.
@@ -80,7 +81,7 @@ class SharpIR : public wpi::Sendable, public wpi::SendableHelper {
*
* @return range of the target returned by the sensor
*/
- units::centimeter_t GetRange() const;
+ units::meter_t GetRange() const;
void InitSendable(wpi::SendableBuilder& builder) override;
@@ -92,8 +93,8 @@ class SharpIR : public wpi::Sendable, public wpi::SendableHelper {
double m_A;
double m_B;
- double m_minCM;
- double m_maxCM;
+ units::meter_t m_min;
+ units::meter_t m_max;
};
} // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h b/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
index 644e348afd8..b6bf76076fa 100644
--- a/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
@@ -25,7 +25,7 @@ class DifferentialDrivetrainSim {
* system can be created with
* LinearSystemId::DrivetrainVelocitySystem() or
* LinearSystemId::IdentifyDrivetrainSystem().
- * @param trackWidth The robot's track width.
+ * @param trackwidth The robot's trackwidth.
* @param driveMotor A DCMotor representing the left side of the drivetrain.
* @param gearingRatio The gearingRatio ratio of the left side, as output over
* input. This must be the same ratio as the ratio used to
@@ -41,7 +41,7 @@ class DifferentialDrivetrainSim {
* starting point.
*/
DifferentialDrivetrainSim(
- LinearSystem<2, 2, 2> plant, units::meter_t trackWidth,
+ LinearSystem<2, 2, 2> plant, units::meter_t trackwidth,
DCMotor driveMotor, double gearingRatio, units::meter_t wheelRadius,
const std::array& measurementStdDevs = {});
@@ -56,7 +56,7 @@ class DifferentialDrivetrainSim {
* center.
* @param mass The mass of the drivebase.
* @param wheelRadius The radius of the wheels on the drivetrain.
- * @param trackWidth The robot's track width, or distance between left and
+ * @param trackwidth The robot's trackwidth, or distance between left and
* right wheels.
* @param measurementStdDevs Standard deviations for measurements, in the form
* [x, y, heading, left velocity, right velocity,
@@ -70,7 +70,7 @@ class DifferentialDrivetrainSim {
DifferentialDrivetrainSim(
frc::DCMotor driveMotor, double gearing, units::kilogram_square_meter_t J,
units::kilogram_t mass, units::meter_t wheelRadius,
- units::meter_t trackWidth,
+ units::meter_t trackwidth,
const std::array& measurementStdDevs = {});
/**
diff --git a/wpilibc/src/main/native/include/frc/simulation/SharpIRSim.h b/wpilibc/src/main/native/include/frc/simulation/SharpIRSim.h
index afbc0f4f9a2..e4c98b03c63 100644
--- a/wpilibc/src/main/native/include/frc/simulation/SharpIRSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/SharpIRSim.h
@@ -31,9 +31,9 @@ class SharpIRSim {
/**
* Set the range returned by the distance sensor.
*
- * @param rng range of the target returned by the sensor
+ * @param range range of the target returned by the sensor
*/
- void SetRange(units::centimeter_t rng);
+ void SetRange(units::meter_t range);
private:
hal::SimDouble m_simRange;
diff --git a/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h b/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
index 0d22d87df5b..1bbde4808ec 100644
--- a/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
@@ -45,7 +45,7 @@ class UltrasonicSim {
*
* @param range The range.
*/
- void SetRange(units::inch_t range);
+ void SetRange(units::meter_t range);
private:
hal::SimBoolean m_simRangeValid;
diff --git a/wpilibc/src/test/native/cpp/SharpIRTest.cpp b/wpilibc/src/test/native/cpp/SharpIRTest.cpp
index e5445eb709d..8456a565e34 100644
--- a/wpilibc/src/test/native/cpp/SharpIRTest.cpp
+++ b/wpilibc/src/test/native/cpp/SharpIRTest.cpp
@@ -13,11 +13,11 @@ TEST(SharpIRTest, SimDevices) {
SharpIR s = SharpIR::GP2Y0A02YK0F(1);
SharpIRSim sim(s);
- EXPECT_EQ(20, s.GetRange().value());
+ EXPECT_EQ(0.2, s.GetRange().value());
- sim.SetRange(units::centimeter_t{30});
- EXPECT_EQ(30, s.GetRange().value());
+ sim.SetRange(30_cm);
+ EXPECT_EQ(0.3, s.GetRange().value());
- sim.SetRange(units::centimeter_t{300});
- EXPECT_EQ(150, s.GetRange().value());
+ sim.SetRange(300_cm);
+ EXPECT_EQ(1.5, s.GetRange().value());
}
diff --git a/wpilibc/src/test/native/cpp/UltrasonicTest.cpp b/wpilibc/src/test/native/cpp/UltrasonicTest.cpp
index ca901dba02a..7ffbc16694f 100644
--- a/wpilibc/src/test/native/cpp/UltrasonicTest.cpp
+++ b/wpilibc/src/test/native/cpp/UltrasonicTest.cpp
@@ -16,7 +16,7 @@ TEST(UltrasonicTest, SimDevices) {
EXPECT_EQ(0, ultrasonic.GetRange().value());
EXPECT_TRUE(ultrasonic.IsRangeValid());
- sim.SetRange(units::meter_t{35.04});
+ sim.SetRange(35.04_m);
EXPECT_EQ(35.04, ultrasonic.GetRange().value());
sim.SetRangeValid(false);
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
index 85bccc7f521..bc57f727d46 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
@@ -56,7 +56,7 @@ class Drivetrain {
void UpdateOdometry();
private:
- static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
+ static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
@@ -73,7 +73,7 @@ class Drivetrain {
frc::AnalogGyro m_gyro{0};
- frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
+ frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
frc::DifferentialDriveOdometry m_odometry{
m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()}};
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
index 633571ef173..bc74a9c90a2 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
@@ -112,7 +112,7 @@ class Drivetrain {
nt::DoubleArrayEntry& cameraToObjectEntry);
private:
- static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
+ static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
static constexpr units::meter_t kWheelRadius = 0.0508_m;
static constexpr int kEncoderResolution = 4096;
@@ -147,7 +147,7 @@ class Drivetrain {
frc::AnalogGyro m_gyro{0};
- frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
+ frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
// Gains are for example purposes only - must be determined for your own
// robot!
@@ -174,5 +174,5 @@ class Drivetrain {
frc::LinearSystemId::IdentifyDrivetrainSystem(
1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
- m_drivetrainSystem, kTrackWidth, frc::DCMotor::CIM(2), 8, 2_in};
+ m_drivetrainSystem, kTrackwidth, frc::DCMotor::CIM(2), 8, 2_in};
};
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
index 99aed4e627a..9fd38043e1f 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Constants.cpp
@@ -7,10 +7,10 @@
namespace DriveConstants {
const frc::MecanumDriveKinematics kDriveKinematics{
- frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
+ frc::Translation2d{kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{kWheelBase / 2, -kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, -kTrackwidth / 2}};
} // namespace DriveConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
index 7dde79c308a..098dfa2028c 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
@@ -43,17 +43,17 @@ inline constexpr bool kRearLeftEncoderReversed = true;
inline constexpr bool kFrontRightEncoderReversed = false;
inline constexpr bool kRearRightEncoderReversed = true;
-inline constexpr auto kTrackWidth =
+inline constexpr auto kTrackwidth =
0.5_m; // Distance between centers of right and left wheels on robot
inline constexpr auto kWheelBase =
0.7_m; // Distance between centers of front and back wheels on robot
extern const frc::MecanumDriveKinematics kDriveKinematics;
inline constexpr int kEncoderCPR = 1024;
-inline constexpr double kWheelDiameterMeters = 0.15;
+inline constexpr auto kWheelDiameter = 0.15_m;
inline constexpr double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * std::numbers::pi) /
+ (kWheelDiameter.value() * std::numbers::pi) /
static_cast(kEncoderCPR);
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
index ca82547f7cb..4320e50508e 100644
--- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
@@ -73,7 +73,7 @@ class Drivetrain {
void Periodic();
private:
- static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
+ static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
@@ -90,7 +90,7 @@ class Drivetrain {
frc::AnalogGyro m_gyro{0};
- frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
+ frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
frc::DifferentialDriveOdometry m_odometry{
m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()}};
@@ -108,5 +108,5 @@ class Drivetrain {
frc::LinearSystemId::IdentifyDrivetrainSystem(
1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
- m_drivetrainSystem, kTrackWidth, frc::DCMotor::CIM(2), 8, 2_in};
+ m_drivetrainSystem, kTrackwidth, frc::DCMotor::CIM(2), 8, 2_in};
};
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
index 5e95629f184..b8c0f76940a 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
@@ -80,10 +80,10 @@ inline constexpr double kPRearRightVel = 0.5;
namespace ModuleConstants {
inline constexpr int kEncoderCPR = 1024;
-inline constexpr double kWheelDiameterMeters = 0.15;
+inline constexpr auto kWheelDiameter = 0.15_m;
inline constexpr double kDriveEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * std::numbers::pi) /
+ (kWheelDiameter.value() * std::numbers::pi) /
static_cast(kEncoderCPR);
inline constexpr double kTurningEncoderDistancePerPulse =
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
index c428fd7f347..d0222961687 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h
@@ -88,16 +88,16 @@ class DriveSubsystem : public frc2::SubsystemBase {
*/
void ResetOdometry(frc::Pose2d pose);
- units::meter_t kTrackWidth =
+ units::meter_t kTrackwidth =
0.5_m; // Distance between centers of right and left wheels on robot
units::meter_t kWheelBase =
0.7_m; // Distance between centers of front and back wheels on robot
frc::SwerveDriveKinematics<4> kDriveKinematics{
- frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
- frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
+ frc::Translation2d{kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{kWheelBase / 2, -kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, kTrackwidth / 2},
+ frc::Translation2d{-kWheelBase / 2, -kTrackwidth / 2}};
private:
// Components (e.g. motor controllers and sensors) should generally be
diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
index fecaf97fb9d..a6b97377d88 100644
--- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
@@ -15,8 +15,8 @@ void Robot::AutonomousInit() {
}
void Robot::AutonomousPeriodic() {
- units::millimeter_t measurement = m_ultrasonic.GetRange();
- units::millimeter_t filteredMeasurement = m_filter.Calculate(measurement);
+ units::meter_t measurement = m_ultrasonic.GetRange();
+ units::meter_t filteredMeasurement = m_filter.Calculate(measurement);
double pidOutput = m_pidController.Calculate(filteredMeasurement.value());
// disable input squaring -- PID output is linear
diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
index 696f0668fc9..165cdbf1fd4 100644
--- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
@@ -23,7 +23,7 @@ class Robot : public frc::TimedRobot {
void AutonomousPeriodic() override;
// distance the robot wants to stay from an object
- static constexpr units::millimeter_t kHoldDistance = 1_m;
+ static constexpr units::meter_t kHoldDistance = 1_m;
static constexpr int kLeftMotorPort = 0;
static constexpr int kRightMotorPort = 1;
@@ -32,7 +32,7 @@ class Robot : public frc::TimedRobot {
private:
// proportional speed constant
- static constexpr double kP = 0.001;
+ static constexpr double kP = 1.0;
// integral speed constant
static constexpr double kI = 0.0;
// derivative speed constant
diff --git a/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp b/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
index 5cfcbe8dbc7..f13fc22bc16 100644
--- a/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
+++ b/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
@@ -2,7 +2,6 @@
// 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.
-#include
#include
#include
@@ -47,7 +46,7 @@ class UltrasonicPIDTest : public testing::TestWithParam {
Robot::kUltrasonicEchoPort};
int32_t m_callback;
- units::millimeter_t m_distance;
+ units::meter_t m_distance;
public:
void SimPeriodicBefore() {
@@ -101,7 +100,7 @@ TEST_P(UltrasonicPIDTest, Auto) {
{
frc::sim::StepTiming(5_s);
- EXPECT_NEAR(Robot::kHoldDistance.value(), m_distance.value(), 10.0);
+ EXPECT_NEAR(Robot::kHoldDistance.value(), m_distance.value(), 0.01);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMA.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMA.java
index bd26a7bf5de..501e7f57de7 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMA.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMA.java
@@ -33,10 +33,10 @@ public void setPause(boolean pause) {
/**
* Sets DMA to trigger at an interval.
*
- * @param periodSeconds Period at which to trigger DMA in seconds.
+ * @param period Period at which to trigger DMA in seconds.
*/
- public void setTimedTrigger(double periodSeconds) {
- DMAJNI.setTimedTrigger(m_dmaHandle, periodSeconds);
+ public void setTimedTrigger(double period) {
+ DMAJNI.setTimedTrigger(m_dmaHandle, period);
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMASample.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMASample.java
index 1435cd36d9d..c07d2cdb049 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMASample.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMASample.java
@@ -58,11 +58,11 @@ public DMASample() {}
* Retrieves a new DMA sample.
*
* @param dma DMA object.
- * @param timeoutSeconds Timeout in seconds for retrieval.
+ * @param timeout Timeout for retrieval in seconds.
* @return DMA read status.
*/
- public DMAReadStatus update(DMA dma, double timeoutSeconds) {
- return DMAReadStatus.getValue(m_dmaSample.update(dma.m_dmaHandle, timeoutSeconds));
+ public DMAReadStatus update(DMA dma, double timeout) {
+ return DMAReadStatus.getValue(m_dmaSample.update(dma.m_dmaHandle, timeout));
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
index 36721e355aa..c75c9ea1b2b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
@@ -1148,19 +1148,19 @@ public static AllianceStationID getRawAllianceStation() {
/**
* Wait for a DS connection.
*
- * @param timeoutSeconds timeout in seconds. 0 for infinite.
+ * @param timeout timeout in seconds. 0 for infinite.
* @return true if connected, false if timeout
*/
- public static boolean waitForDsConnection(double timeoutSeconds) {
+ public static boolean waitForDsConnection(double timeout) {
int event = WPIUtilJNI.createEvent(true, false);
DriverStationJNI.provideNewDataEventHandle(event);
boolean result;
try {
- if (timeoutSeconds == 0) {
+ if (timeout == 0) {
WPIUtilJNI.waitForObject(event);
result = true;
} else {
- result = !WPIUtilJNI.waitForObjectTimeout(event, timeoutSeconds);
+ result = !WPIUtilJNI.waitForObjectTimeout(event, timeout);
}
} catch (InterruptedException ex) {
Thread.currentThread().interrupt();
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
index 1529af5bc69..3c4543cfcde 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
@@ -31,11 +31,11 @@ public class Notifier implements AutoCloseable {
// The time, in seconds, at which the callback should be called. Has the same
// zero as RobotController.getFPGATime().
- private double m_expirationTimeSeconds;
+ private double m_expirationTime;
- // If periodic, stores the callback period; if single, stores the time until
- // the callback call.
- private double m_periodSeconds;
+ // If periodic, stores the callback period in seconds; if single, stores the time until
+ // the callback call in seconds.
+ private double m_period;
// True if the callback is periodic
private boolean m_periodic;
@@ -75,7 +75,7 @@ private void updateAlarm(long triggerTimeMicroS) {
/** Update the alarm hardware to reflect the next alarm. */
private void updateAlarm() {
- updateAlarm((long) (m_expirationTimeSeconds * 1e6));
+ updateAlarm((long) (m_expirationTime * 1e6));
}
/**
@@ -109,7 +109,7 @@ public Notifier(Runnable callback) {
try {
threadHandler = m_callback;
if (m_periodic) {
- m_expirationTimeSeconds += m_periodSeconds;
+ m_expirationTime += m_period;
updateAlarm();
} else {
// Need to update the alarm to cause it to wait again
@@ -178,8 +178,8 @@ public void startSingle(double delaySeconds) {
m_processLock.lock();
try {
m_periodic = false;
- m_periodSeconds = delaySeconds;
- m_expirationTimeSeconds = RobotController.getFPGATime() * 1e-6 + delaySeconds;
+ m_period = delaySeconds;
+ m_expirationTime = RobotController.getFPGATime() * 1e-6 + delaySeconds;
updateAlarm();
} finally {
m_processLock.unlock();
@@ -192,15 +192,15 @@ public void startSingle(double delaySeconds) {
* The user-provided callback should be written so that it completes before the next time it's
* scheduled to run.
*
- * @param periodSeconds Period in seconds after which to to call the callback starting one period
- * after the call to this method.
+ * @param period Period in seconds after which to to call the callback starting one period after
+ * the call to this method.
*/
- public void startPeriodic(double periodSeconds) {
+ public void startPeriodic(double period) {
m_processLock.lock();
try {
m_periodic = true;
- m_periodSeconds = periodSeconds;
- m_expirationTimeSeconds = RobotController.getFPGATime() * 1e-6 + periodSeconds;
+ m_period = period;
+ m_expirationTime = RobotController.getFPGATime() * 1e-6 + period;
updateAlarm();
} finally {
m_processLock.unlock();
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java
index 66993da1b2f..67b39234750 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java
@@ -7,6 +7,7 @@
import edu.wpi.first.hal.SimDevice;
import edu.wpi.first.hal.SimDevice.Direction;
import edu.wpi.first.hal.SimDouble;
+import edu.wpi.first.math.MathUtil;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
@@ -27,47 +28,47 @@ public class SharpIR implements Sendable, AutoCloseable {
private final double m_A;
private final double m_B;
- private final double m_minCM;
- private final double m_maxCM;
+ private final double m_min; // m
+ private final double m_max; // m
/**
- * Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20cm to 150cm.
+ * Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20 cm to 150 cm.
*
* @param channel Analog input channel the sensor is connected to
* @return sensor object
*/
public static SharpIR GP2Y0A02YK0F(int channel) {
- return new SharpIR(channel, 62.28, -1.092, 20, 150.0);
+ return new SharpIR(channel, 62.28, -1.092, 0.2, 1.5);
}
/**
- * Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10cm to 80cm.
+ * Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10 cm to 80 cm.
*
* @param channel Analog input channel the sensor is connected to
* @return sensor object
*/
public static SharpIR GP2Y0A21YK0F(int channel) {
- return new SharpIR(channel, 26.449, -1.226, 10.0, 80.0);
+ return new SharpIR(channel, 26.449, -1.226, 0.1, 0.8);
}
/**
- * Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4cm to 30cm.
+ * Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4 cm to 30 cm.
*
* @param channel Analog input channel the sensor is connected to
* @return sensor object
*/
public static SharpIR GP2Y0A41SK0F(int channel) {
- return new SharpIR(channel, 12.354, -1.07, 4.0, 30.0);
+ return new SharpIR(channel, 12.354, -1.07, 0.04, 0.3);
}
/**
- * Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2cm to 15cm.
+ * Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2 cm to 15 cm.
*
* @param channel Analog input channel the sensor is connected to
* @return sensor object
*/
public static SharpIR GP2Y0A51SK0F(int channel) {
- return new SharpIR(channel, 5.2819, -1.161, 2.0, 15.0);
+ return new SharpIR(channel, 5.2819, -1.161, 0.02, 0.15);
}
/**
@@ -77,23 +78,23 @@ public static SharpIR GP2Y0A51SK0F(int channel) {
* @param channel AnalogInput channel
* @param a Constant A
* @param b Constant B
- * @param minCM Minimum distance to report in centimeters
- * @param maxCM Maximum distance to report in centimeters
+ * @param min Minimum distance to report in meters
+ * @param max Maximum distance to report in meters
*/
@SuppressWarnings("this-escape")
- public SharpIR(int channel, double a, double b, double minCM, double maxCM) {
+ public SharpIR(int channel, double a, double b, double min, double max) {
m_sensor = new AnalogInput(channel);
m_A = a;
m_B = b;
- m_minCM = minCM;
- m_maxCM = maxCM;
+ m_min = min;
+ m_max = max;
SendableRegistry.addLW(this, "SharpIR", channel);
m_simDevice = SimDevice.create("SharpIR", m_sensor.getChannel());
if (m_simDevice != null) {
- m_simRange = m_simDevice.createDouble("Range (cm)", Direction.kInput, 0.0);
+ m_simRange = m_simDevice.createDouble("Range (m)", Direction.kInput, 0.0);
m_sensor.setSimDevice(m_simDevice);
}
}
@@ -121,37 +122,24 @@ public int getChannel() {
}
/**
- * Get the range in inches from the distance sensor.
+ * Get the range in meters from the distance sensor.
*
- * @return range in inches of the target returned by the sensor
+ * @return range in meters of the target returned by the sensor
*/
- public double getRangeInches() {
- return getRangeCM() / 2.54;
- }
-
- /**
- * Get the range in centimeters from the distance sensor.
- *
- * @return range in centimeters of the target returned by the sensor
- */
- public double getRangeCM() {
- double distance;
-
+ public double getRange() {
if (m_simRange != null) {
- distance = m_simRange.get();
+ return MathUtil.clamp(m_simRange.get(), m_min, m_max);
} else {
// Don't allow zero/negative values
var v = Math.max(m_sensor.getVoltage(), 0.00001);
- distance = m_A * Math.pow(v, m_B);
- }
- // Always constrain output
- return Math.max(Math.min(distance, m_maxCM), m_minCM);
+ return MathUtil.clamp(m_A * Math.pow(v, m_B) * 1e-2, m_min, m_max);
+ }
}
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Ultrasonic");
- builder.addDoubleProperty("Value", this::getRangeInches, null);
+ builder.addDoubleProperty("Value", this::getRange, null);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
index 449402c6cdf..c9b7a9ea65b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
@@ -87,14 +87,14 @@ public void close() {
/**
* Wait for an interrupt.
*
- * @param timeoutSeconds The timeout in seconds. 0 or less will return immediately.
+ * @param timeout The timeout in seconds. 0 or less will return immediately.
* @param ignorePrevious True to ignore if a previous interrupt has occurred, and only wait for a
* new trigger. False will consider if an interrupt has occurred since the last time the
* interrupt was read.
* @return Result of which edges were triggered, or if a timeout occurred.
*/
- public WaitResult waitForInterrupt(double timeoutSeconds, boolean ignorePrevious) {
- long result = InterruptJNI.waitForInterrupt(m_handle, timeoutSeconds, ignorePrevious);
+ public WaitResult waitForInterrupt(double timeout, boolean ignorePrevious) {
+ long result = InterruptJNI.waitForInterrupt(m_handle, timeout, ignorePrevious);
// Rising edge result is the interrupt bit set in the byte 0xFF
// Falling edge result is the interrupt bit set in the byte 0xFF00
@@ -108,11 +108,11 @@ public WaitResult waitForInterrupt(double timeoutSeconds, boolean ignorePrevious
/**
* Wait for an interrupt, ignoring any previously occurring interrupts.
*
- * @param timeoutSeconds The timeout in seconds. 0 or less will return immediately.
+ * @param timeout The timeout in seconds. 0 or less will return immediately.
* @return Result of which edges were triggered, or if a timeout occurred.
*/
- public WaitResult waitForInterrupt(double timeoutSeconds) {
- return waitForInterrupt(timeoutSeconds, true);
+ public WaitResult waitForInterrupt(double timeout) {
+ return waitForInterrupt(timeout, true);
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
index 78a8046f3d6..9c80653a8e1 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
@@ -32,19 +32,18 @@ static class Callback implements Comparable {
* Construct a callback container.
*
* @param func The callback to run.
- * @param startTimeSeconds The common starting point for all callback scheduling in
- * microseconds.
- * @param periodSeconds The period at which to run the callback in microseconds.
- * @param offsetSeconds The offset from the common starting time in microseconds.
+ * @param startTime The common starting point for all callback scheduling in microseconds.
+ * @param period The period at which to run the callback in microseconds.
+ * @param offset The offset from the common starting time in microseconds.
*/
- Callback(Runnable func, long startTimeUs, long periodUs, long offsetUs) {
+ Callback(Runnable func, long startTime, long period, long offset) {
this.func = func;
- this.period = periodUs;
+ this.period = period;
this.expirationTime =
- startTimeUs
- + offsetUs
+ startTime
+ + offset
+ this.period
- + (RobotController.getFPGATime() - startTimeUs) / this.period * this.period;
+ + (RobotController.getFPGATime() - startTime) / this.period * this.period;
}
@Override
@@ -180,10 +179,10 @@ public long getLoopStartTime() {
* synchronously. Interactions between them are thread-safe.
*
* @param callback The callback to run.
- * @param periodSeconds The period at which to run the callback in seconds.
+ * @param period The period at which to run the callback in seconds.
*/
- public final void addPeriodic(Runnable callback, double periodSeconds) {
- m_callbacks.add(new Callback(callback, m_startTimeUs, (long) (periodSeconds * 1e6), 0));
+ public final void addPeriodic(Runnable callback, double period) {
+ m_callbacks.add(new Callback(callback, m_startTimeUs, (long) (period * 1e6), 0));
}
/**
@@ -193,14 +192,13 @@ public final void addPeriodic(Runnable callback, double periodSeconds) {
* synchronously. Interactions between them are thread-safe.
*
* @param callback The callback to run.
- * @param periodSeconds The period at which to run the callback in seconds.
- * @param offsetSeconds The offset from the common starting time in seconds. This is useful for
+ * @param period The period at which to run the callback in seconds.
+ * @param offset The offset from the common starting time in seconds. This is useful for
* scheduling a callback in a different timeslot relative to TimedRobot.
*/
- public final void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) {
+ public final void addPeriodic(Runnable callback, double period, double offset) {
m_callbacks.add(
- new Callback(
- callback, m_startTimeUs, (long) (periodSeconds * 1e6), (long) (offsetSeconds * 1e6)));
+ new Callback(callback, m_startTimeUs, (long) (period * 1e6), (long) (offset * 1e6)));
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
index 14103544ce3..8bf619a1df6 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
@@ -30,7 +30,7 @@
public class Ultrasonic implements Sendable, AutoCloseable {
// Time (sec) for the ping trigger pulse.
private static final double kPingTime = 10 * 1e-6;
- private static final double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+ private static final double kSpeedOfSound = 344.4; // m/s
// ultrasonic sensor list
private static final List m_sensors = new ArrayList<>();
// automatic round robin mode
@@ -88,7 +88,7 @@ private synchronized void initialize() {
m_simDevice = SimDevice.create("Ultrasonic", m_echoChannel.getChannel());
if (m_simDevice != null) {
m_simRangeValid = m_simDevice.createBoolean("Range Valid", Direction.kInput, true);
- m_simRange = m_simDevice.createDouble("Range (in)", Direction.kInput, 0.0);
+ m_simRange = m_simDevice.createDouble("Range (m)", Direction.kInput, 0.0);
m_pingChannel.setSimDevice(m_simDevice);
m_echoChannel.setSimDevice(m_simDevice);
}
@@ -276,32 +276,22 @@ public boolean isRangeValid() {
}
/**
- * Get the range in inches from the ultrasonic sensor. If there is no valid value yet, i.e. at
+ * Get the range in meters from the ultrasonic sensor. If there is no valid value yet, i.e. at
* least one measurement hasn't completed, then return 0.
*
- * @return double Range in inches of the target returned from the ultrasonic sensor.
+ * @return double Range in meters of the target returned by the ultrasonic sensor.
*/
- public double getRangeInches() {
+ public double getRange() {
if (isRangeValid()) {
if (m_simRange != null) {
return m_simRange.get();
}
- return m_counter.getPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+ return m_counter.getPeriod() * kSpeedOfSound / 2.0;
} else {
return 0;
}
}
- /**
- * Get the range in millimeters from the ultrasonic sensor. If there is no valid value yet, i.e.
- * at least one measurement hasn't completed, then return 0.
- *
- * @return double Range in millimeters of the target returned by the ultrasonic sensor.
- */
- public double getRangeMM() {
- return getRangeInches() * 25.4;
- }
-
/**
* Is the ultrasonic enabled.
*
@@ -323,6 +313,6 @@ public void setEnabled(boolean enable) {
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Ultrasonic");
- builder.addDoubleProperty("Value", this::getRangeInches, null);
+ builder.addDoubleProperty("Value", this::getRange, null);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
index 6d00d6402bb..a59f9638ffd 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -21,9 +21,9 @@ public class Watchdog implements Closeable, Comparable {
// Used for timeout print rate-limiting
private static final long kMinPrintPeriodMicroS = (long) 1e6;
- private double m_startTimeSeconds;
- private double m_timeoutSeconds;
- private double m_expirationTimeSeconds;
+ private double m_startTime;
+ private double m_timeout;
+ private double m_expirationTime;
private final Runnable m_callback;
private double m_lastTimeoutPrintSeconds;
@@ -46,11 +46,11 @@ public class Watchdog implements Closeable, Comparable {
/**
* Watchdog constructor.
*
- * @param timeoutSeconds The watchdog's timeout in seconds with microsecond resolution.
+ * @param timeout The watchdog's timeout in seconds with microsecond resolution.
* @param callback This function is called when the timeout expires.
*/
- public Watchdog(double timeoutSeconds, Runnable callback) {
- m_timeoutSeconds = timeoutSeconds;
+ public Watchdog(double timeout, Runnable callback) {
+ m_timeout = timeout;
m_callback = callback;
m_tracer = new Tracer();
}
@@ -63,19 +63,19 @@ public void close() {
@Override
public boolean equals(Object obj) {
return obj instanceof Watchdog watchdog
- && Double.compare(m_expirationTimeSeconds, watchdog.m_expirationTimeSeconds) == 0;
+ && Double.compare(m_expirationTime, watchdog.m_expirationTime) == 0;
}
@Override
public int hashCode() {
- return Double.hashCode(m_expirationTimeSeconds);
+ return Double.hashCode(m_expirationTime);
}
@Override
public int compareTo(Watchdog rhs) {
// Elements with sooner expiration times are sorted as lesser. The head of
// Java's PriorityQueue is the least element.
- return Double.compare(m_expirationTimeSeconds, rhs.m_expirationTimeSeconds);
+ return Double.compare(m_expirationTime, rhs.m_expirationTime);
}
/**
@@ -84,25 +84,25 @@ public int compareTo(Watchdog rhs) {
* @return The time in seconds since the watchdog was last fed.
*/
public double getTime() {
- return Timer.getFPGATimestamp() - m_startTimeSeconds;
+ return Timer.getFPGATimestamp() - m_startTime;
}
/**
* Sets the watchdog's timeout.
*
- * @param timeoutSeconds The watchdog's timeout in seconds with microsecond resolution.
+ * @param timeout The watchdog's timeout in seconds with microsecond resolution.
*/
- public void setTimeout(double timeoutSeconds) {
- m_startTimeSeconds = Timer.getFPGATimestamp();
+ public void setTimeout(double timeout) {
+ m_startTime = Timer.getFPGATimestamp();
m_tracer.clearEpochs();
m_queueMutex.lock();
try {
- m_timeoutSeconds = timeoutSeconds;
+ m_timeout = timeout;
m_isExpired = false;
m_watchdogs.remove(this);
- m_expirationTimeSeconds = m_startTimeSeconds + m_timeoutSeconds;
+ m_expirationTime = m_startTime + m_timeout;
m_watchdogs.add(this);
updateAlarm();
} finally {
@@ -118,7 +118,7 @@ public void setTimeout(double timeoutSeconds) {
public double getTimeout() {
m_queueMutex.lock();
try {
- return m_timeoutSeconds;
+ return m_timeout;
} finally {
m_queueMutex.unlock();
}
@@ -168,7 +168,7 @@ public void reset() {
/** Enables the watchdog timer. */
public void enable() {
- m_startTimeSeconds = Timer.getFPGATimestamp();
+ m_startTime = Timer.getFPGATimestamp();
m_tracer.clearEpochs();
m_queueMutex.lock();
@@ -176,7 +176,7 @@ public void enable() {
m_isExpired = false;
m_watchdogs.remove(this);
- m_expirationTimeSeconds = m_startTimeSeconds + m_timeoutSeconds;
+ m_expirationTime = m_startTime + m_timeout;
m_watchdogs.add(this);
updateAlarm();
} finally {
@@ -212,7 +212,7 @@ private static void updateAlarm() {
NotifierJNI.cancelNotifierAlarm(m_notifier);
} else {
NotifierJNI.updateNotifierAlarm(
- m_notifier, (long) (m_watchdogs.peek().m_expirationTimeSeconds * 1e6));
+ m_notifier, (long) (m_watchdogs.peek().m_expirationTime * 1e6));
}
}
@@ -245,7 +245,7 @@ private static void schedulerFunc() {
watchdog.m_lastTimeoutPrintSeconds = now;
if (!watchdog.m_suppressTimeoutMessage) {
DriverStation.reportWarning(
- String.format("Watchdog not fed within %.6fs\n", watchdog.m_timeoutSeconds), false);
+ String.format("Watchdog not fed within %.6fs\n", watchdog.m_timeout), false);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
index f94fa35b9c7..627c35c7fad 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
@@ -95,27 +95,27 @@ public void setGyroRateZ(double angularRateDegreesPerSecond) {
/**
* Sets the X axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelX(double accelMetersPerSecondSquared) {
- m_simAccelX.set(accelMetersPerSecondSquared);
+ public void setAccelX(double accel) {
+ m_simAccelX.set(accel);
}
/**
* Sets the Y axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelY(double accelMetersPerSecondSquared) {
- m_simAccelY.set(accelMetersPerSecondSquared);
+ public void setAccelY(double accel) {
+ m_simAccelY.set(accel);
}
/**
* Sets the Z axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelZ(double accelMetersPerSecondSquared) {
- m_simAccelZ.set(accelMetersPerSecondSquared);
+ public void setAccelZ(double accel) {
+ m_simAccelZ.set(accel);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
index 57262440a69..d7a1d001b1b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
@@ -95,27 +95,27 @@ public void setGyroRateZ(double angularRateDegreesPerSecond) {
/**
* Sets the X axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelX(double accelMetersPerSecondSquared) {
- m_simAccelX.set(accelMetersPerSecondSquared);
+ public void setAccelX(double accel) {
+ m_simAccelX.set(accel);
}
/**
* Sets the Y axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelY(double accelMetersPerSecondSquared) {
- m_simAccelY.set(accelMetersPerSecondSquared);
+ public void setAccelY(double accel) {
+ m_simAccelY.set(accel);
}
/**
* Sets the Z axis acceleration in meters per second squared.
*
- * @param accelMetersPerSecondSquared The acceleration.
+ * @param accel The acceleration in m/s².
*/
- public void setAccelZ(double accelMetersPerSecondSquared) {
- m_simAccelZ.set(accelMetersPerSecondSquared);
+ public void setAccelZ(double accel) {
+ m_simAccelZ.set(accel);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
index f89b6440a8f..a9e7d361fba 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
@@ -4,19 +4,11 @@
package edu.wpi.first.wpilibj.simulation;
-import static edu.wpi.first.units.Units.Radians;
-import static edu.wpi.first.units.Units.RadiansPerSecond;
-import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond;
-
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N2;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
-import edu.wpi.first.math.util.Units;
-import edu.wpi.first.units.measure.Angle;
-import edu.wpi.first.units.measure.AngularAcceleration;
-import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.wpilibj.RobotController;
/** Represents a simulated DC motor mechanism. */
@@ -27,8 +19,8 @@ public class DCMotorSim extends LinearSystemSim {
// The gearing from the motors to the output.
private final double m_gearing;
- // The moment of inertia for the DC motor mechanism.
- private final double m_jKgMetersSquared;
+ // The moment of inertia for the DC motor mechanism in kg-m².
+ private final double m_j;
/**
* Creates a simulated DC motor mechanism.
@@ -64,36 +56,36 @@ public DCMotorSim(LinearSystem plant, DCMotor gearbox, double... mea
//
// B = GKₜ/(RJ)
// J = GKₜ/(RB)
- m_gearing = -gearbox.KvRadPerSecPerVolt * plant.getA(1, 1) / plant.getB(1, 0);
- m_jKgMetersSquared = m_gearing * gearbox.KtNMPerAmp / (gearbox.rOhms * plant.getB(1, 0));
+ m_gearing = -gearbox.Kv * plant.getA(1, 1) / plant.getB(1, 0);
+ m_j = m_gearing * gearbox.Kt / (gearbox.R * plant.getB(1, 0));
}
/**
* Sets the state of the DC motor.
*
- * @param angularPositionRad The new position in radians.
- * @param angularVelocityRadPerSec The new velocity in radians per second.
+ * @param angularPosition The new position in radians.
+ * @param angularVelocity The new velocity in radians per second.
*/
- public void setState(double angularPositionRad, double angularVelocityRadPerSec) {
- setState(VecBuilder.fill(angularPositionRad, angularVelocityRadPerSec));
+ public void setState(double angularPosition, double angularVelocity) {
+ setState(VecBuilder.fill(angularPosition, angularVelocity));
}
/**
* Sets the DC motor's angular position.
*
- * @param angularPositionRad The new position in radians.
+ * @param angularPosition The new position in radians.
*/
- public void setAngle(double angularPositionRad) {
- setState(angularPositionRad, getAngularVelocityRadPerSec());
+ public void setAngle(double angularPosition) {
+ setState(angularPosition, getAngularVelocity());
}
/**
* Sets the DC motor's angular velocity.
*
- * @param angularVelocityRadPerSec The new velocity in radians per second.
+ * @param angularVelocity The new velocity in radians per second.
*/
- public void setAngularVelocity(double angularVelocityRadPerSec) {
- setState(getAngularPositionRad(), angularVelocityRadPerSec);
+ public void setAngularVelocity(double angularVelocity) {
+ setState(getAngularPosition(), angularVelocity);
}
/**
@@ -108,10 +100,10 @@ public double getGearing() {
/**
* Returns the moment of inertia of the DC motor.
*
- * @return The DC motor's moment of inertia.
+ * @return The DC motor's moment of inertia in kg-m².
*/
- public double getJKgMetersSquared() {
- return m_jKgMetersSquared;
+ public double getJ() {
+ return m_j;
}
/**
@@ -126,91 +118,46 @@ public DCMotor getGearbox() {
/**
* Returns the DC motor's position.
*
- * @return The DC motor's position.
+ * @return The DC motor's position in meters.
*/
- public double getAngularPositionRad() {
+ public double getAngularPosition() {
return getOutput(0);
}
- /**
- * Returns the DC motor's position in rotations.
- *
- * @return The DC motor's position in rotations.
- */
- public double getAngularPositionRotations() {
- return Units.radiansToRotations(getAngularPositionRad());
- }
-
- /**
- * Returns the DC motor's position.
- *
- * @return The DC motor's position
- */
- public Angle getAngularPosition() {
- return Radians.of(getAngularPositionRad());
- }
-
/**
* Returns the DC motor's velocity.
*
* @return The DC motor's velocity.
*/
- public double getAngularVelocityRadPerSec() {
+ public double getAngularVelocity() {
return getOutput(1);
}
/**
- * Returns the DC motor's velocity in RPM.
- *
- * @return The DC motor's velocity in RPM.
- */
- public double getAngularVelocityRPM() {
- return Units.radiansPerSecondToRotationsPerMinute(getAngularVelocityRadPerSec());
- }
-
- /**
- * Returns the DC motor's velocity.
- *
- * @return The DC motor's velocity
- */
- public AngularVelocity getAngularVelocity() {
- return RadiansPerSecond.of(getAngularVelocityRadPerSec());
- }
-
- /**
- * Returns the DC motor's acceleration in Radians Per Second Squared.
+ * Returns the DC motor's acceleration.
*
- * @return The DC motor's acceleration in Radians Per Second Squared.
+ * @return The DC motor's acceleration in rad/s².
*/
- public double getAngularAccelerationRadPerSecSq() {
+ public double getAngularAcceleration() {
var acceleration = (m_plant.getA().times(m_x)).plus(m_plant.getB().times(m_u));
return acceleration.get(1, 0);
}
/**
- * Returns the DC motor's acceleration.
- *
- * @return The DC motor's acceleration.
- */
- public AngularAcceleration getAngularAcceleration() {
- return RadiansPerSecondPerSecond.of(getAngularAccelerationRadPerSecSq());
- }
-
- /**
- * Returns the DC motor's torque in Newton-Meters.
+ * Returns the DC motor's torque in.
*
- * @return The DC motor's torque in Newton-Meters.
+ * @return The DC motor's torque in Newton-meters.
*/
- public double getTorqueNewtonMeters() {
- return getAngularAccelerationRadPerSecSq() * m_jKgMetersSquared;
+ public double getTorque() {
+ return getAngularAcceleration() * m_j;
}
/**
* Returns the DC motor's current draw.
*
- * @return The DC motor's current draw.
+ * @return The DC motor's current draw in amps.
*/
- public double getCurrentDrawAmps() {
+ public double getCurrentDraw() {
// I = V / R - omega / (Kv * R)
// Reductions are output over input, so a reduction of 2:1 means the motor is spinning
// 2x faster than the output
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
index 6e25b344393..5ecfd55fcae 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java
@@ -42,7 +42,7 @@ public class DifferentialDrivetrainSim {
private final double m_originalGearing;
private final Matrix m_measurementStdDevs;
private double m_currentGearing;
- private final double m_wheelRadiusMeters;
+ private final double m_wheelRadius;
private Matrix m_u;
private Matrix m_x;
@@ -57,10 +57,10 @@ public class DifferentialDrivetrainSim {
* @param driveMotor A {@link DCMotor} representing the left side of the drivetrain.
* @param gearing The gearing ratio between motor and wheel, as output over input. This must be
* the same ratio as the ratio used to identify or create the drivetrainPlant.
- * @param jKgMetersSquared The moment of inertia of the drivetrain about its center.
- * @param massKg The mass of the drivebase.
- * @param wheelRadiusMeters The radius of the wheels on the drivetrain.
- * @param trackWidthMeters The robot's track width, or distance between left and right wheels.
+ * @param j The moment of inertia of the drivetrain about its center in kg-m².
+ * @param mass The mass of the drivebase in kg.
+ * @param wheelRadius The radius of the wheels on the drivetrain in meters.
+ * @param trackwidth The robot's trackwidth, or distance between left and right wheels, in meters.
* @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
* left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
* desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
@@ -70,23 +70,18 @@ public class DifferentialDrivetrainSim {
public DifferentialDrivetrainSim(
DCMotor driveMotor,
double gearing,
- double jKgMetersSquared,
- double massKg,
- double wheelRadiusMeters,
- double trackWidthMeters,
+ double j,
+ double mass,
+ double wheelRadius,
+ double trackwidth,
Matrix measurementStdDevs) {
this(
LinearSystemId.createDrivetrainVelocitySystem(
- driveMotor,
- massKg,
- wheelRadiusMeters,
- trackWidthMeters / 2.0,
- jKgMetersSquared,
- gearing),
+ driveMotor, mass, wheelRadius, trackwidth / 2.0, j, gearing),
driveMotor,
gearing,
- trackWidthMeters,
- wheelRadiusMeters,
+ trackwidth,
+ wheelRadius,
measurementStdDevs);
}
@@ -102,9 +97,9 @@ public DifferentialDrivetrainSim(
* @param driveMotor A {@link DCMotor} representing the drivetrain.
* @param gearing The gearingRatio ratio of the robot, as output over input. This must be the same
* ratio as the ratio used to identify or create the drivetrainPlant.
- * @param trackWidthMeters The distance between the two sides of the drivetrain. Can be found with
- * SysId.
- * @param wheelRadiusMeters The radius of the wheels on the drivetrain, in meters.
+ * @param trackwidth The distance between the two sides of the drivetrain in meters. Can be found
+ * with SysId.
+ * @param wheelRadius The radius of the wheels on the drivetrain, in meters.
* @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
* left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
* desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
@@ -115,15 +110,15 @@ public DifferentialDrivetrainSim(
LinearSystem plant,
DCMotor driveMotor,
double gearing,
- double trackWidthMeters,
- double wheelRadiusMeters,
+ double trackwidth,
+ double wheelRadius,
Matrix measurementStdDevs) {
this.m_plant = plant;
- this.m_rb = trackWidthMeters / 2.0;
+ this.m_rb = trackwidth / 2.0;
this.m_motor = driveMotor;
this.m_originalGearing = gearing;
this.m_measurementStdDevs = measurementStdDevs;
- m_wheelRadiusMeters = wheelRadiusMeters;
+ m_wheelRadius = wheelRadius;
m_currentGearing = m_originalGearing;
m_x = new Matrix<>(Nat.N7(), Nat.N1());
@@ -145,10 +140,10 @@ public void setInputs(double leftVoltageVolts, double rightVoltageVolts) {
/**
* Update the drivetrain states with the current time difference.
*
- * @param dtSeconds the time difference
+ * @param dt the time difference in seconds
*/
- public void update(double dtSeconds) {
- m_x = NumericalIntegration.rkdp(this::getDynamics, m_x, m_u, dtSeconds);
+ public void update(double dt) {
+ m_x = NumericalIntegration.rkdp(this::getDynamics, m_x, m_u, dt);
m_y = m_x;
if (m_measurementStdDevs != null) {
m_y = m_y.plus(StateSpaceUtil.makeWhiteNoiseVector(m_measurementStdDevs));
@@ -195,38 +190,38 @@ public Pose2d getPose() {
}
/**
- * Get the right encoder position in meters.
+ * Get the right encoder position.
*
- * @return The encoder position.
+ * @return The encoder position in meters.
*/
- public double getRightPositionMeters() {
+ public double getRightPosition() {
return getOutput(State.kRightPosition);
}
/**
- * Get the right encoder velocity in meters per second.
+ * Get the right encoder velocity.
*
- * @return The encoder velocity.
+ * @return The encoder velocity in meters per second.
*/
- public double getRightVelocityMetersPerSecond() {
+ public double getRightVelocity() {
return getOutput(State.kRightVelocity);
}
/**
- * Get the left encoder position in meters.
+ * Get the left encoder position.
*
- * @return The encoder position.
+ * @return The encoder position in meters.
*/
- public double getLeftPositionMeters() {
+ public double getLeftPosition() {
return getOutput(State.kLeftPosition);
}
/**
- * Get the left encoder velocity in meters per second.
+ * Get the left encoder velocity.
*
- * @return The encoder velocity.
+ * @return The encoder velocity in meters per second.
*/
- public double getLeftVelocityMetersPerSecond() {
+ public double getLeftVelocity() {
return getOutput(State.kLeftVelocity);
}
@@ -235,9 +230,9 @@ public double getLeftVelocityMetersPerSecond() {
*
* @return the drivetrain's left side current draw, in amps
*/
- public double getLeftCurrentDrawAmps() {
+ public double getLeftCurrentDraw() {
return m_motor.getCurrent(
- getState(State.kLeftVelocity) * m_currentGearing / m_wheelRadiusMeters, m_u.get(0, 0))
+ getState(State.kLeftVelocity) * m_currentGearing / m_wheelRadius, m_u.get(0, 0))
* Math.signum(m_u.get(0, 0));
}
@@ -246,9 +241,9 @@ public double getLeftCurrentDrawAmps() {
*
* @return the drivetrain's right side current draw, in amps
*/
- public double getRightCurrentDrawAmps() {
+ public double getRightCurrentDraw() {
return m_motor.getCurrent(
- getState(State.kRightVelocity) * m_currentGearing / m_wheelRadiusMeters, m_u.get(1, 0))
+ getState(State.kRightVelocity) * m_currentGearing / m_wheelRadius, m_u.get(1, 0))
* Math.signum(m_u.get(1, 0));
}
@@ -257,8 +252,8 @@ public double getRightCurrentDrawAmps() {
*
* @return the current draw, in amps
*/
- public double getCurrentDrawAmps() {
- return getLeftCurrentDrawAmps() + getRightCurrentDrawAmps();
+ public double getCurrentDraw() {
+ return getLeftCurrentDraw() + getRightCurrentDraw();
}
/**
@@ -472,8 +467,7 @@ public static DifferentialDrivetrainSim createKitbotSim(
* @param motor The motors installed in the bot.
* @param gearing The gearing reduction used.
* @param wheelSize The wheel size.
- * @param jKgMetersSquared The moment of inertia of the drivebase. This can be calculated using
- * SysId.
+ * @param j The moment of inertia of the drivebase in kg-m². This can be calculated using SysId.
* @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
* left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
* desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
@@ -485,12 +479,12 @@ public static DifferentialDrivetrainSim createKitbotSim(
KitbotMotor motor,
KitbotGearing gearing,
KitbotWheelSize wheelSize,
- double jKgMetersSquared,
+ double j,
Matrix measurementStdDevs) {
return new DifferentialDrivetrainSim(
motor.value,
gearing.value,
- jKgMetersSquared,
+ j,
Units.lbsToKilograms(60),
wheelSize.value / 2.0,
Units.inchesToMeters(26),
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
index 2f7ce3e768d..c5d80589410 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java
@@ -36,10 +36,10 @@ public class ElevatorSim extends LinearSystemSim {
* {@link edu.wpi.first.math.system.plant.LinearSystemId#createElevatorSystem(DCMotor, double,
* double, double)}.
* @param gearbox The type of and number of motors in the elevator gearbox.
- * @param minHeightMeters The min allowable height of the elevator.
- * @param maxHeightMeters The max allowable height of the elevator.
+ * @param minHeight The min allowable height of the elevator.
+ * @param maxHeight The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
- * @param startingHeightMeters The starting height of the elevator.
+ * @param startingHeight The starting height of the elevator.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for position.
*/
@@ -47,18 +47,18 @@ public class ElevatorSim extends LinearSystemSim {
public ElevatorSim(
LinearSystem plant,
DCMotor gearbox,
- double minHeightMeters,
- double maxHeightMeters,
+ double minHeight,
+ double maxHeight,
boolean simulateGravity,
- double startingHeightMeters,
+ double startingHeight,
double... measurementStdDevs) {
super(plant, measurementStdDevs);
m_gearbox = gearbox;
- m_minHeight = minHeightMeters;
- m_maxHeight = maxHeightMeters;
+ m_minHeight = minHeight;
+ m_maxHeight = maxHeight;
m_simulateGravity = simulateGravity;
- setState(startingHeightMeters, 0);
+ setState(startingHeight, 0);
}
/**
@@ -67,10 +67,10 @@ public ElevatorSim(
* @param kV The velocity gain.
* @param kA The acceleration gain.
* @param gearbox The type of and number of motors in the elevator gearbox.
- * @param minHeightMeters The min allowable height of the elevator.
- * @param maxHeightMeters The max allowable height of the elevator.
+ * @param minHeight The min allowable height of the elevator.
+ * @param maxHeight The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
- * @param startingHeightMeters The starting height of the elevator.
+ * @param startingHeight The starting height of the elevator.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for position.
*/
@@ -78,18 +78,18 @@ public ElevatorSim(
double kV,
double kA,
DCMotor gearbox,
- double minHeightMeters,
- double maxHeightMeters,
+ double minHeight,
+ double maxHeight,
boolean simulateGravity,
- double startingHeightMeters,
+ double startingHeight,
double... measurementStdDevs) {
this(
LinearSystemId.identifyPositionSystem(kV, kA),
gearbox,
- minHeightMeters,
- maxHeightMeters,
+ minHeight,
+ maxHeight,
simulateGravity,
- startingHeightMeters,
+ startingHeight,
measurementStdDevs);
}
@@ -98,32 +98,32 @@ public ElevatorSim(
*
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param gearing The gearing of the elevator (numbers greater than 1 represent reductions).
- * @param carriageMassKg The mass of the elevator carriage.
- * @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
- * @param minHeightMeters The min allowable height of the elevator.
- * @param maxHeightMeters The max allowable height of the elevator.
+ * @param carriageMass The mass of the elevator carriage.
+ * @param drumRadius The radius of the drum that the elevator spool is wrapped around.
+ * @param minHeight The min allowable height of the elevator.
+ * @param maxHeight The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
- * @param startingHeightMeters The starting height of the elevator.
+ * @param startingHeight The starting height of the elevator.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for position.
*/
public ElevatorSim(
DCMotor gearbox,
double gearing,
- double carriageMassKg,
- double drumRadiusMeters,
- double minHeightMeters,
- double maxHeightMeters,
+ double carriageMass,
+ double drumRadius,
+ double minHeight,
+ double maxHeight,
boolean simulateGravity,
- double startingHeightMeters,
+ double startingHeight,
double... measurementStdDevs) {
this(
- LinearSystemId.createElevatorSystem(gearbox, carriageMassKg, drumRadiusMeters, gearing),
+ LinearSystemId.createElevatorSystem(gearbox, carriageMass, drumRadius, gearing),
gearbox,
- minHeightMeters,
- maxHeightMeters,
+ minHeight,
+ maxHeight,
simulateGravity,
- startingHeightMeters,
+ startingHeight,
measurementStdDevs);
}
@@ -131,33 +131,31 @@ public ElevatorSim(
* Sets the elevator's state. The new position will be limited between the minimum and maximum
* allowed heights.
*
- * @param positionMeters The new position in meters.
- * @param velocityMetersPerSecond New velocity in meters per second.
+ * @param position The new position in meters.
+ * @param velocity New velocity in meters per second.
*/
- public final void setState(double positionMeters, double velocityMetersPerSecond) {
- setState(
- VecBuilder.fill(
- MathUtil.clamp(positionMeters, m_minHeight, m_maxHeight), velocityMetersPerSecond));
+ public final void setState(double position, double velocity) {
+ setState(VecBuilder.fill(MathUtil.clamp(position, m_minHeight, m_maxHeight), velocity));
}
/**
* Returns whether the elevator would hit the lower limit.
*
- * @param elevatorHeightMeters The elevator height.
+ * @param elevatorHeight The elevator height.
* @return Whether the elevator would hit the lower limit.
*/
- public boolean wouldHitLowerLimit(double elevatorHeightMeters) {
- return elevatorHeightMeters <= this.m_minHeight;
+ public boolean wouldHitLowerLimit(double elevatorHeight) {
+ return elevatorHeight <= this.m_minHeight;
}
/**
* Returns whether the elevator would hit the upper limit.
*
- * @param elevatorHeightMeters The elevator height.
+ * @param elevatorHeight The elevator height.
* @return Whether the elevator would hit the upper limit.
*/
- public boolean wouldHitUpperLimit(double elevatorHeightMeters) {
- return elevatorHeightMeters >= this.m_maxHeight;
+ public boolean wouldHitUpperLimit(double elevatorHeight) {
+ return elevatorHeight >= this.m_maxHeight;
}
/**
@@ -166,7 +164,7 @@ public boolean wouldHitUpperLimit(double elevatorHeightMeters) {
* @return Whether the elevator has hit the lower limit.
*/
public boolean hasHitLowerLimit() {
- return wouldHitLowerLimit(getPositionMeters());
+ return wouldHitLowerLimit(getPosition());
}
/**
@@ -175,43 +173,42 @@ public boolean hasHitLowerLimit() {
* @return Whether the elevator has hit the upper limit.
*/
public boolean hasHitUpperLimit() {
- return wouldHitUpperLimit(getPositionMeters());
+ return wouldHitUpperLimit(getPosition());
}
/**
* Returns the position of the elevator.
*
- * @return The position of the elevator.
+ * @return The position of the elevator in meters.
*/
- public double getPositionMeters() {
+ public double getPosition() {
return getOutput(0);
}
/**
* Returns the velocity of the elevator.
*
- * @return The velocity of the elevator.
+ * @return The velocity of the elevator in meters per second.
*/
- public double getVelocityMetersPerSecond() {
+ public double getVelocity() {
return getOutput(1);
}
/**
* Returns the elevator current draw.
*
- * @return The elevator current draw.
+ * @return The elevator current draw in amps.
*/
- public double getCurrentDrawAmps() {
+ public double getCurrentDraw() {
// I = V / R - omega / (Kv * R)
// Reductions are greater than 1, so a reduction of 10:1 would mean the motor is
// spinning 10x faster than the output
// v = r w, so w = v/r
double kA = 1 / m_plant.getB().get(1, 0);
double kV = -m_plant.getA().get(1, 1) * kA;
- double motorVelocityRadPerSec = m_x.get(1, 0) * kV * m_gearbox.KvRadPerSecPerVolt;
+ double motorVelocity = m_x.get(1, 0) * kV * m_gearbox.Kv;
var appliedVoltage = m_u.get(0, 0);
- return m_gearbox.getCurrent(motorVelocityRadPerSec, appliedVoltage)
- * Math.signum(appliedVoltage);
+ return m_gearbox.getCurrent(motorVelocity, appliedVoltage) * Math.signum(appliedVoltage);
}
/**
@@ -229,10 +226,10 @@ public void setInputVoltage(double volts) {
*
* @param currentXhat The current state estimate.
* @param u The system inputs (voltage).
- * @param dtSeconds The time difference between controller updates.
+ * @param dt The time difference between controller updates.
*/
@Override
- protected Matrix updateX(Matrix currentXhat, Matrix u, double dtSeconds) {
+ protected Matrix updateX(Matrix currentXhat, Matrix u, double dt) {
// Calculate updated x-hat from Runge-Kutta.
var updatedXhat =
NumericalIntegration.rkdp(
@@ -245,7 +242,7 @@ protected Matrix updateX(Matrix currentXhat, Matrix u, d
},
currentXhat,
u,
- dtSeconds);
+ dt);
// We check for collisions after updating x-hat.
if (wouldHitLowerLimit(updatedXhat.get(0, 0))) {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
index 95d01e16217..e9e72b0894c 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
@@ -4,17 +4,11 @@
package edu.wpi.first.wpilibj.simulation;
-import static edu.wpi.first.units.Units.RadiansPerSecond;
-import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond;
-
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
-import edu.wpi.first.math.util.Units;
-import edu.wpi.first.units.measure.AngularAcceleration;
-import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.wpilibj.RobotController;
/** Represents a simulated flywheel mechanism. */
@@ -26,7 +20,7 @@ public class FlywheelSim extends LinearSystemSim {
private final double m_gearing;
// The moment of inertia for the flywheel mechanism.
- private final double m_jKgMetersSquared;
+ private final double m_j;
/**
* Creates a simulated flywheel mechanism.
@@ -60,17 +54,17 @@ public FlywheelSim(
//
// B = GKₜ/(RJ)
// J = GKₜ/(RB)
- m_gearing = -gearbox.KvRadPerSecPerVolt * plant.getA(0, 0) / plant.getB(0, 0);
- m_jKgMetersSquared = m_gearing * gearbox.KtNMPerAmp / (gearbox.rOhms * plant.getB(0, 0));
+ m_gearing = -gearbox.Kv * plant.getA(0, 0) / plant.getB(0, 0);
+ m_j = m_gearing * gearbox.Kt / (gearbox.R * plant.getB(0, 0));
}
/**
* Sets the flywheel's angular velocity.
*
- * @param velocityRadPerSec The new velocity in radians per second.
+ * @param velocity The new velocity in radians per second.
*/
- public void setAngularVelocity(double velocityRadPerSec) {
- setState(VecBuilder.fill(velocityRadPerSec));
+ public void setAngularVelocity(double velocity) {
+ setState(VecBuilder.fill(velocity));
}
/**
@@ -83,12 +77,12 @@ public double getGearing() {
}
/**
- * Returns the moment of inertia in kilograms meters squared.
+ * Returns the moment of inertia.
*
- * @return The flywheel's moment of inertia.
+ * @return The flywheel's moment of inertia in kg-m².
*/
- public double getJKgMetersSquared() {
- return m_jKgMetersSquared;
+ public double getJ() {
+ return m_j;
}
/**
@@ -100,67 +94,40 @@ public DCMotor getGearbox() {
return m_gearbox;
}
- /**
- * Returns the flywheel's velocity in Radians Per Second.
- *
- * @return The flywheel's velocity in Radians Per Second.
- */
- public double getAngularVelocityRadPerSec() {
- return getOutput(0);
- }
-
- /**
- * Returns the flywheel's velocity in RPM.
- *
- * @return The flywheel's velocity in RPM.
- */
- public double getAngularVelocityRPM() {
- return Units.radiansPerSecondToRotationsPerMinute(getAngularVelocityRadPerSec());
- }
-
/**
* Returns the flywheel's velocity.
*
- * @return The flywheel's velocity
+ * @return The flywheel's velocity in rad/s.
*/
- public AngularVelocity getAngularVelocity() {
- return RadiansPerSecond.of(getAngularVelocityRadPerSec());
+ public double getAngularVelocity() {
+ return getOutput(0);
}
/**
- * Returns the flywheel's acceleration in Radians Per Second Squared.
+ * Returns the flywheel's acceleration.
*
- * @return The flywheel's acceleration in Radians Per Second Squared.
+ * @return The flywheel's acceleration in rad/s².
*/
- public double getAngularAccelerationRadPerSecSq() {
+ public double getAngularAcceleration() {
var acceleration = (m_plant.getA().times(m_x)).plus(m_plant.getB().times(m_u));
return acceleration.get(0, 0);
}
/**
- * Returns the flywheel's acceleration.
- *
- * @return The flywheel's acceleration.
- */
- public AngularAcceleration getAngularAcceleration() {
- return RadiansPerSecondPerSecond.of(getAngularAccelerationRadPerSecSq());
- }
-
- /**
- * Returns the flywheel's torque in Newton-Meters.
+ * Returns the flywheel's torque.
*
- * @return The flywheel's torque in Newton-Meters.
+ * @return The flywheel's torque in Newton-meters.
*/
- public double getTorqueNewtonMeters() {
- return getAngularAccelerationRadPerSecSq() * m_jKgMetersSquared;
+ public double getTorque() {
+ return getAngularAcceleration() * m_j;
}
/**
* Returns the flywheel's current draw.
*
- * @return The flywheel's current draw.
+ * @return The flywheel's current draw in amps.
*/
- public double getCurrentDrawAmps() {
+ public double getCurrentDraw() {
// I = V / R - omega / (Kv * R)
// Reductions are output over input, so a reduction of 2:1 means the motor is spinning
// 2x faster than the flywheel
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
index ec296fde3d8..65270a24a64 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
@@ -72,11 +72,11 @@ public LinearSystemSim(
/**
* Updates the simulation.
*
- * @param dtSeconds The time between updates.
+ * @param dt The time between updates in seconds.
*/
- public void update(double dtSeconds) {
+ public void update(double dt) {
// Update X. By default, this is the linear system dynamics X = Ax + Bu
- m_x = updateX(m_x, m_u, dtSeconds);
+ m_x = updateX(m_x, m_u, dt);
// y = cx + du
m_y = m_plant.calculateY(m_x, m_u);
@@ -171,12 +171,12 @@ public void setState(Matrix state) {
*
* @param currentXhat The current state estimate.
* @param u The system inputs (usually voltage).
- * @param dtSeconds The time difference between controller updates.
+ * @param dt The time difference between controller updates.
* @return The new state.
*/
protected Matrix updateX(
- Matrix currentXhat, Matrix u, double dtSeconds) {
- return m_plant.calculateX(currentXhat, u, dtSeconds);
+ Matrix currentXhat, Matrix u, double dt) {
+ return m_plant.calculateX(currentXhat, u, dt);
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SharpIRSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SharpIRSim.java
index eaf3dcb8b10..4d90f2c5c0b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SharpIRSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SharpIRSim.java
@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.simulation;
import edu.wpi.first.hal.SimDouble;
-import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.SharpIR;
/** Simulation class for Sharp IR sensors. */
@@ -28,24 +27,15 @@ public SharpIRSim(SharpIR sharpIR) {
*/
public SharpIRSim(int channel) {
SimDeviceSim simDevice = new SimDeviceSim("SharpIR", channel);
- m_simRange = simDevice.getDouble("Range (cm)");
+ m_simRange = simDevice.getDouble("Range (m)");
}
/**
- * Set the range in inches returned by the distance sensor.
+ * Set the range in meters returned by the distance sensor.
*
- * @param inches range in inches of the target returned by the sensor
+ * @param range range in meters of the target returned by the sensor
*/
- public void setRangeInches(double inches) {
- m_simRange.set(Units.inchesToMeters(inches) * 100.0);
- }
-
- /**
- * Set the range in centimeters returned by the distance sensor.
- *
- * @param cm range in centimeters of the target returned by the sensor
- */
- public void setRangeCm(double cm) {
- m_simRange.set(cm);
+ public void setRange(double range) {
+ m_simRange.set(range);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
index 7d7ae78284d..318b3c179ee 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java
@@ -24,7 +24,7 @@ public class SingleJointedArmSim extends LinearSystemSim {
private final double m_gearing;
// The length of the arm.
- private final double m_armLenMeters;
+ private final double m_armLength;
// The minimum angle that the arm is capable of.
private final double m_minAngle;
@@ -43,7 +43,7 @@ public class SingleJointedArmSim extends LinearSystemSim {
* double, double)}.
* @param gearbox The type of and number of motors in the arm gearbox.
* @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
- * @param armLengthMeters The length of the arm.
+ * @param armLength The length of the arm in meters.
* @param minAngleRads The minimum angle that the arm is capable of.
* @param maxAngleRads The maximum angle that the arm is capable of.
* @param simulateGravity Whether gravity should be simulated or not.
@@ -56,7 +56,7 @@ public SingleJointedArmSim(
LinearSystem plant,
DCMotor gearbox,
double gearing,
- double armLengthMeters,
+ double armLength,
double minAngleRads,
double maxAngleRads,
boolean simulateGravity,
@@ -65,7 +65,7 @@ public SingleJointedArmSim(
super(plant, measurementStdDevs);
m_gearbox = gearbox;
m_gearing = gearing;
- m_armLenMeters = armLengthMeters;
+ m_armLength = armLength;
m_minAngle = minAngleRads;
m_maxAngle = maxAngleRads;
m_simulateGravity = simulateGravity;
@@ -78,8 +78,8 @@ public SingleJointedArmSim(
*
* @param gearbox The type of and number of motors in the arm gearbox.
* @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
- * @param jKgMetersSquared The moment of inertia of the arm; can be calculated from CAD software.
- * @param armLengthMeters The length of the arm.
+ * @param j The moment of inertia of the arm in kg-m²; can be calculated from CAD software.
+ * @param armLength The length of the arm in meters.
* @param minAngleRads The minimum angle that the arm is capable of.
* @param maxAngleRads The maximum angle that the arm is capable of.
* @param simulateGravity Whether gravity should be simulated or not.
@@ -90,18 +90,18 @@ public SingleJointedArmSim(
public SingleJointedArmSim(
DCMotor gearbox,
double gearing,
- double jKgMetersSquared,
- double armLengthMeters,
+ double j,
+ double armLength,
double minAngleRads,
double maxAngleRads,
boolean simulateGravity,
double startingAngleRads,
double... measurementStdDevs) {
this(
- LinearSystemId.createSingleJointedArmSystem(gearbox, jKgMetersSquared, gearing),
+ LinearSystemId.createSingleJointedArmSystem(gearbox, j, gearing),
gearbox,
gearing,
- armLengthMeters,
+ armLength,
minAngleRads,
maxAngleRads,
simulateGravity,
@@ -162,7 +162,7 @@ public boolean hasHitUpperLimit() {
/**
* Returns the current arm angle.
*
- * @return The current arm angle.
+ * @return The current arm angle in radians.
*/
public double getAngleRads() {
return getOutput(0);
@@ -171,9 +171,9 @@ public double getAngleRads() {
/**
* Returns the current arm velocity.
*
- * @return The current arm velocity.
+ * @return The current arm velocity in radians per second.
*/
- public double getVelocityRadPerSec() {
+ public double getVelocity() {
return getOutput(1);
}
@@ -182,7 +182,7 @@ public double getVelocityRadPerSec() {
*
* @return The arm current draw.
*/
- public double getCurrentDrawAmps() {
+ public double getCurrentDraw() {
// Reductions are greater than 1, so a reduction of 10:1 would mean the motor is
// spinning 10x faster than the output
var motorVelocity = m_x.get(1, 0) * m_gearing;
@@ -202,12 +202,12 @@ public void setInputVoltage(double volts) {
/**
* Calculates a rough estimate of the moment of inertia of an arm given its length and mass.
*
- * @param lengthMeters The length of the arm.
- * @param massKg The mass of the arm.
- * @return The calculated moment of inertia.
+ * @param length The length of the arm in m.
+ * @param mass The mass of the arm in kg.
+ * @return The calculated moment of inertia in kg-m².
*/
- public static double estimateMOI(double lengthMeters, double massKg) {
- return 1.0 / 3.0 * massKg * lengthMeters * lengthMeters;
+ public static double estimateMOI(double length, double mass) {
+ return 1.0 / 3.0 * mass * length * length;
}
/**
@@ -215,10 +215,10 @@ public static double estimateMOI(double lengthMeters, double massKg) {
*
* @param currentXhat The current state estimate.
* @param u The system inputs (voltage).
- * @param dtSeconds The time difference between controller updates.
+ * @param dt The time difference between controller updates in seconds.
*/
@Override
- protected Matrix updateX(Matrix currentXhat, Matrix u, double dtSeconds) {
+ protected Matrix updateX(Matrix currentXhat, Matrix u, double dt) {
// The torque on the arm is given by τ = F⋅r, where F is the force applied by
// gravity and r the distance from pivot to center of mass. Recall from
// dynamics that the sum of torques for a rigid body is τ = J⋅α, were τ is
@@ -248,14 +248,14 @@ protected Matrix updateX(Matrix currentXhat, Matrix u, d
(Matrix x, Matrix _u) -> {
Matrix xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
if (m_simulateGravity) {
- double alphaGrav = 3.0 / 2.0 * -9.8 * Math.cos(x.get(0, 0)) / m_armLenMeters;
+ double alphaGrav = 3.0 / 2.0 * -9.8 * Math.cos(x.get(0, 0)) / m_armLength;
xdot = xdot.plus(VecBuilder.fill(0, alphaGrav));
}
return xdot;
},
currentXhat,
u,
- dtSeconds);
+ dt);
// We check for collision after updating xhat
if (wouldHitLowerLimit(updatedXhat.get(0, 0))) {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/UltrasonicSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/UltrasonicSim.java
index 2ad42e7afaf..0e8f53473ea 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/UltrasonicSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/UltrasonicSim.java
@@ -6,7 +6,6 @@
import edu.wpi.first.hal.SimBoolean;
import edu.wpi.first.hal.SimDouble;
-import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Ultrasonic;
/** Class to control a simulated {@link edu.wpi.first.wpilibj.Ultrasonic}. */
@@ -33,7 +32,7 @@ public UltrasonicSim(Ultrasonic ultrasonic) {
public UltrasonicSim(@SuppressWarnings("unused") int ping, int echo) {
SimDeviceSim simDevice = new SimDeviceSim("Ultrasonic", echo);
m_simRangeValid = simDevice.getBoolean("Range Valid");
- m_simRange = simDevice.getDouble("Range (in)");
+ m_simRange = simDevice.getDouble("Range (m)");
}
/**
@@ -48,18 +47,9 @@ public void setRangeValid(boolean valid) {
/**
* Sets the range measurement.
*
- * @param inches The range in inches.
+ * @param range The range in meters.
*/
- public void setRangeInches(double inches) {
- m_simRange.set(inches);
- }
-
- /**
- * Sets the range measurement.
- *
- * @param meters The range in meters.
- */
- public void setRangeMeters(double meters) {
- m_simRange.set(Units.metersToInches(meters));
+ public void setRange(double range) {
+ m_simRange.set(range);
}
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
index 7ce6af8c3e8..749e2f843e6 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java
@@ -58,12 +58,12 @@ public synchronized void setRobotPose(Pose2d pose) {
/**
* Set the robot pose from x, y, and rotation.
*
- * @param xMeters X location, in meters
- * @param yMeters Y location, in meters
+ * @param x X location, in meters
+ * @param y Y location, in meters
* @param rotation rotation
*/
- public synchronized void setRobotPose(double xMeters, double yMeters, Rotation2d rotation) {
- m_objects.get(0).setPose(xMeters, yMeters, rotation);
+ public synchronized void setRobotPose(double x, double y, Rotation2d rotation) {
+ m_objects.get(0).setPose(x, y, rotation);
}
/**
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
index f3627a6bef1..c943a1d317f 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
@@ -43,12 +43,12 @@ public synchronized void setPose(Pose2d pose) {
/**
* Set the pose from x, y, and rotation.
*
- * @param xMeters X location, in meters
- * @param yMeters Y location, in meters
+ * @param x X location, in meters
+ * @param y Y location, in meters
* @param rotation rotation
*/
- public synchronized void setPose(double xMeters, double yMeters, Rotation2d rotation) {
- setPose(new Pose2d(xMeters, yMeters, rotation));
+ public synchronized void setPose(double x, double y, Rotation2d rotation) {
+ setPose(new Pose2d(x, y, rotation));
}
/**
@@ -94,7 +94,7 @@ public synchronized void setPoses(Pose2d... poses) {
public synchronized void setTrajectory(Trajectory trajectory) {
m_poses.clear();
for (Trajectory.State state : trajectory.getStates()) {
- m_poses.add(state.poseMeters);
+ m_poses.add(state.pose);
}
updateEntry();
}
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SharpIRTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SharpIRTest.java
index 1ae35ae781d..4049dc805ab 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SharpIRTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SharpIRTest.java
@@ -15,13 +15,13 @@ void testSharpIR() {
try (SharpIR s = SharpIR.GP2Y0A02YK0F(1)) {
SharpIRSim sim = new SharpIRSim(s);
- assertEquals(20, s.getRangeCM());
+ assertEquals(0.2, s.getRange());
- sim.setRangeCm(30);
- assertEquals(30, s.getRangeCM());
+ sim.setRange(0.3);
+ assertEquals(0.3, s.getRange());
- sim.setRangeCm(300);
- assertEquals(150, s.getRangeCM());
+ sim.setRange(3);
+ assertEquals(1.5, s.getRange());
}
}
}
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java
index da5eac71b3d..9105b07a848 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java
@@ -20,15 +20,15 @@ void testUltrasonic() {
try (Ultrasonic ultrasonic = new Ultrasonic(0, 1)) {
UltrasonicSim sim = new UltrasonicSim(ultrasonic);
- assertEquals(0, ultrasonic.getRangeInches());
+ assertEquals(0, ultrasonic.getRange());
assertTrue(ultrasonic.isRangeValid());
- sim.setRangeInches(35.04);
- assertEquals(35.04, ultrasonic.getRangeInches());
+ sim.setRange(35.04);
+ assertEquals(35.04, ultrasonic.getRange());
sim.setRangeValid(false);
assertFalse(ultrasonic.isRangeValid());
- assertEquals(0, ultrasonic.getRangeInches());
+ assertEquals(0, ultrasonic.getRange());
}
}
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DCMotorSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DCMotorSimTest.java
index b7a4a6dd875..d7f141eb56e 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DCMotorSimTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DCMotorSimTest.java
@@ -36,23 +36,23 @@ void testVoltageSteadyState() {
// ------ SimulationPeriodic() happens after user code -------
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw()));
sim.setInputVoltage(motor.get() * RobotController.getBatteryVoltage());
sim.update(0.020);
- encoderSim.setRate(sim.getAngularVelocityRadPerSec());
+ encoderSim.setRate(sim.getAngularVelocity());
}
- assertEquals(gearbox.KvRadPerSecPerVolt * 12, encoder.getRate(), 0.1);
+ assertEquals(gearbox.Kv * 12, encoder.getRate(), 0.1);
for (int i = 0; i < 100; i++) {
motor.setVoltage(0);
// ------ SimulationPeriodic() happens after user code -------
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw()));
sim.setInputVoltage(motor.get() * RobotController.getBatteryVoltage());
sim.update(0.020);
- encoderSim.setRate(sim.getAngularVelocityRadPerSec());
+ encoderSim.setRate(sim.getAngularVelocity());
}
assertEquals(0, encoder.getRate(), 0.1);
@@ -78,11 +78,11 @@ void testPositionFeedbackControl() {
// ------ SimulationPeriodic() happens after user code -------
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(sim.getCurrentDraw()));
sim.setInputVoltage(motor.get() * RobotController.getBatteryVoltage());
sim.update(0.020);
- encoderSim.setDistance(sim.getAngularPositionRad());
- encoderSim.setRate(sim.getAngularVelocityRadPerSec());
+ encoderSim.setDistance(sim.getAngularPosition());
+ encoderSim.setRate(sim.getAngularVelocity());
}
assertEquals(750, encoder.getDistance(), 1.0);
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java
index 25bbdb59834..9d767dee210 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java
@@ -42,7 +42,7 @@ void testConvergence() {
plant,
motor,
1,
- kinematics.trackWidthMeters,
+ kinematics.trackwidth,
Units.inchesToMeters(2),
VecBuilder.fill(0, 0, 0.0001, 0.1, 0.1, 0.005, 0.005));
@@ -61,15 +61,13 @@ void testConvergence() {
new TrajectoryConfig(1, 1)
.addConstraint(new DifferentialDriveKinematicsConstraint(kinematics, 1)));
- for (double t = 0; t < traj.getTotalTimeSeconds(); t += 0.020) {
+ for (double t = 0; t < traj.getTotalTime(); t += 0.020) {
var state = traj.sample(t);
var feedbackOut = feedback.calculate(sim.getPose(), state);
var wheelSpeeds = kinematics.toWheelSpeeds(feedbackOut);
- var voltages =
- feedforward.calculate(
- VecBuilder.fill(wheelSpeeds.leftMetersPerSecond, wheelSpeeds.rightMetersPerSecond));
+ var voltages = feedforward.calculate(VecBuilder.fill(wheelSpeeds.left, wheelSpeeds.right));
// Sim periodic code
sim.setInputs(voltages.get(0, 0), voltages.get(1, 0));
@@ -104,25 +102,25 @@ void testCurrent() {
var kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(24));
var sim =
new DifferentialDrivetrainSim(
- plant, motor, 1, kinematics.trackWidthMeters, Units.inchesToMeters(2), null);
+ plant, motor, 1, kinematics.trackwidth, Units.inchesToMeters(2), null);
sim.setInputs(-12, -12);
for (int i = 0; i < 10; i++) {
sim.update(0.020);
}
- assertTrue(sim.getCurrentDrawAmps() > 0);
+ assertTrue(sim.getCurrentDraw() > 0);
sim.setInputs(12, 12);
for (int i = 0; i < 20; i++) {
sim.update(0.020);
}
- assertTrue(sim.getCurrentDrawAmps() > 0);
+ assertTrue(sim.getCurrentDraw() > 0);
sim.setInputs(-12, 12);
for (int i = 0; i < 30; i++) {
sim.update(0.020);
}
- assertTrue(sim.getCurrentDrawAmps() > 0);
+ assertTrue(sim.getCurrentDraw() > 0);
}
@Test
@@ -138,7 +136,7 @@ void testModelStability() {
plant,
motor,
5,
- kinematics.trackWidthMeters,
+ kinematics.trackwidth,
Units.inchesToMeters(2),
VecBuilder.fill(0, 0, 0.0001, 0.1, 0.1, 0.005, 0.005));
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
index deade245fa1..260bc2772aa 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java
@@ -59,7 +59,7 @@ void testStateSpaceSimWithElevator() {
encoderSim.setDistance(y.get(0, 0));
}
- assertEquals(controller.getSetpoint(), sim.getPositionMeters(), 0.2);
+ assertEquals(controller.getSetpoint(), sim.getPosition(), 0.2);
}
}
@@ -81,14 +81,14 @@ void testMinMax() {
for (int i = 0; i < 100; i++) {
sim.setInput(VecBuilder.fill(0));
sim.update(0.020);
- var height = sim.getPositionMeters();
+ var height = sim.getPosition();
assertTrue(height >= -0.05);
}
for (int i = 0; i < 100; i++) {
sim.setInput(VecBuilder.fill(12.0));
sim.update(0.020);
- var height = sim.getPositionMeters();
+ var height = sim.getPosition();
assertTrue(height <= 1.05);
}
}
@@ -110,7 +110,7 @@ void testStability() {
DCMotor.getVex775Pro(4), 4, Units.inchesToMeters(0.5), 100);
assertEquals(
system.calculateX(VecBuilder.fill(0, 0), VecBuilder.fill(12), 0.02 * 50.0).get(0, 0),
- sim.getPositionMeters(),
+ sim.getPosition(),
0.01);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/subsystems/Arm.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/subsystems/Arm.java
index 3c92370019e..a23e96b2484 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/subsystems/Arm.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/subsystems/Arm.java
@@ -95,7 +95,7 @@ public void simulationPeriodic() {
m_encoderSim.setDistance(m_armSim.getAngleRads());
// SimBattery estimates loaded battery voltages
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(m_armSim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(m_armSim.getCurrentDraw()));
// Update the Mechanism Arm angle based on the simulated arm angle
m_arm.setAngle(Units.radiansToDegrees(m_armSim.getAngleRads()));
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
index adc52e2ef67..cce08317330 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
@@ -19,7 +19,7 @@ public class Drivetrain {
public static final double kMaxSpeed = 3.0; // meters per second
public static final double kMaxAngularSpeed = 2 * Math.PI; // one rotation per second
- private static final double kTrackWidth = 0.381 * 2; // meters
+ private static final double kTrackwidth = 0.381 * 2; // meters
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
@@ -37,7 +37,7 @@ public class Drivetrain {
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
private final DifferentialDriveKinematics m_kinematics =
- new DifferentialDriveKinematics(kTrackWidth);
+ new DifferentialDriveKinematics(kTrackwidth);
private final DifferentialDriveOdometry m_odometry;
@@ -79,13 +79,12 @@ public Drivetrain() {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
- final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
- final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
+ final double leftFeedforward = m_feedforward.calculate(speeds.left);
+ final double rightFeedforward = m_feedforward.calculate(speeds.right);
- final double leftOutput =
- m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
+ final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.left);
final double rightOutput =
- m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
+ m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.right);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
index fbf6e90b9c9..a3f0d9e53c3 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
@@ -43,7 +43,7 @@ public class Drivetrain {
public static final double kMaxSpeed = 3.0; // meters per second
public static final double kMaxAngularSpeed = 2 * Math.PI; // one rotation per second
- private static final double kTrackWidth = 0.381 * 2; // meters
+ private static final double kTrackwidth = 0.381 * 2; // meters
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
@@ -61,7 +61,7 @@ public class Drivetrain {
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
private final DifferentialDriveKinematics m_kinematics =
- new DifferentialDriveKinematics(kTrackWidth);
+ new DifferentialDriveKinematics(kTrackwidth);
private final Pose3d m_objectInField;
@@ -98,7 +98,7 @@ public class Drivetrain {
LinearSystemId.identifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3);
private final DifferentialDrivetrainSim m_drivetrainSimulator =
new DifferentialDrivetrainSim(
- m_drivetrainSystem, DCMotor.getCIM(2), 8, kTrackWidth, kWheelRadius, null);
+ m_drivetrainSystem, DCMotor.getCIM(2), 8, kTrackwidth, kWheelRadius, null);
/**
* Constructs a differential drive object. Sets the encoder distance per pulse and resets the
@@ -139,13 +139,12 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
- final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
- final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
+ final double leftFeedforward = m_feedforward.calculate(speeds.left);
+ final double rightFeedforward = m_feedforward.calculate(speeds.right);
- final double leftOutput =
- m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
+ final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.left);
final double rightOutput =
- m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
+ m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.right);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
@@ -253,10 +252,10 @@ public void simulationPeriodic() {
m_rightLeader.get() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
- m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
- m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocityMetersPerSecond());
- m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
- m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
+ m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPosition());
+ m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocity());
+ m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPosition());
+ m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocity());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
index 1748045c49c..c19622510ea 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
@@ -24,14 +24,14 @@ public static final class DriveConstants {
// These characterization values MUST be determined either experimentally or theoretically
// for *your* robot's drive.
// The SysId tool provides a convenient method for obtaining these values for your robot.
- public static final double ksVolts = 1;
- public static final double kvVoltSecondsPerMeter = 0.8;
- public static final double kaVoltSecondsSquaredPerMeter = 0.15;
+ public static final double ks = 1; // V
+ public static final double kv = 0.8; // V/(m/s)
+ public static final double ka = 0.15; // V/(m/s²)
public static final double kp = 1;
- public static final double kMaxSpeedMetersPerSecond = 3;
- public static final double kMaxAccelerationMetersPerSecondSquared = 3;
+ public static final double kMaxSpeed = 3; // m/s
+ public static final double kMaxAcceleration = 3; // m/s²
}
public static final class OIConstants {
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java
index 3c3179dcc03..19959a61366 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java
@@ -33,10 +33,7 @@ public class DriveSubsystem extends SubsystemBase {
// The feedforward controller.
private final SimpleMotorFeedforward m_feedforward =
- new SimpleMotorFeedforward(
- DriveConstants.ksVolts,
- DriveConstants.kvVoltSecondsPerMeter,
- DriveConstants.kaVoltSecondsSquaredPerMeter);
+ new SimpleMotorFeedforward(DriveConstants.ks, DriveConstants.kv, DriveConstants.ka);
// The robot's drive
private final DifferentialDrive m_drive =
@@ -46,8 +43,7 @@ public class DriveSubsystem extends SubsystemBase {
private final TrapezoidProfile m_profile =
new TrapezoidProfile(
new TrapezoidProfile.Constraints(
- DriveConstants.kMaxSpeedMetersPerSecond,
- DriveConstants.kMaxAccelerationMetersPerSecondSquared));
+ DriveConstants.kMaxSpeed, DriveConstants.kMaxAcceleration));
// The timer
private final Timer m_timer = new Timer();
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Constants.java
index 7a6a937fee4..d0ec6bf51cd 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Constants.java
@@ -26,11 +26,11 @@ public class Constants {
public static final double kElevatorDrumRadius = Units.inchesToMeters(1.0);
public static final double kCarriageMass = Units.lbsToKilograms(12); // kg
- public static final double kSetpointMeters = Units.inchesToMeters(42.875);
- public static final double kLowerkSetpointMeters = Units.inchesToMeters(15);
+ public static final double kSetpoint = Units.inchesToMeters(42.875);
+ public static final double kLowerkSetpoint = Units.inchesToMeters(15);
// Encoder is reset to measure 0 at the bottom, so minimum height is 0.
- public static final double kMinElevatorHeightMeters = 0.0;
- public static final double kMaxElevatorHeightMeters = Units.inchesToMeters(50);
+ public static final double kMinElevatorHeight = 0.0; // m
+ public static final double kMaxElevatorHeight = Units.inchesToMeters(50);
// distance per pulse = (distance per revolution) / (pulses per revolution)
// = (Pi * D) / ppr
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java
index 889fe8e9b32..ef72be7f902 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/Robot.java
@@ -38,10 +38,10 @@ public void teleopInit() {
public void teleopPeriodic() {
if (m_joystick.getTrigger()) {
// Here, we set the constant setpoint of 10 meters.
- m_elevator.reachGoal(Constants.kSetpointMeters);
+ m_elevator.reachGoal(Constants.kSetpoint);
} else {
// Otherwise, we update the setpoint to 1 meter.
- m_elevator.reachGoal(Constants.kLowerkSetpointMeters);
+ m_elevator.reachGoal(Constants.kLowerkSetpoint);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/subsystems/Elevator.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/subsystems/Elevator.java
index 3b2765a9907..b98f5caff42 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/subsystems/Elevator.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialsimulation/subsystems/Elevator.java
@@ -58,8 +58,8 @@ public class Elevator implements AutoCloseable {
Constants.kElevatorGearing,
Constants.kCarriageMass,
Constants.kElevatorDrumRadius,
- Constants.kMinElevatorHeightMeters,
- Constants.kMaxElevatorHeightMeters,
+ Constants.kMinElevatorHeight,
+ Constants.kMaxElevatorHeight,
true,
0,
0.005,
@@ -73,8 +73,7 @@ public class Elevator implements AutoCloseable {
private final MechanismRoot2d m_mech2dRoot =
m_mech2d.getRoot("Elevator Root", Units.inchesToMeters(5), Units.inchesToMeters(0.5));
private final MechanismLigament2d m_elevatorMech2d =
- m_mech2dRoot.append(
- new MechanismLigament2d("Elevator", m_elevatorSim.getPositionMeters(), 90));
+ m_mech2dRoot.append(new MechanismLigament2d("Elevator", m_elevatorSim.getPosition(), 90));
/** Subsystem constructor. */
public Elevator() {
@@ -95,10 +94,10 @@ public void simulationPeriodic() {
m_elevatorSim.update(0.020);
// Finally, we set our simulated encoder's readings and simulated battery voltage
- m_encoderSim.setDistance(m_elevatorSim.getPositionMeters());
+ m_encoderSim.setDistance(m_elevatorSim.getPosition());
// SimBattery estimates loaded battery voltages
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDraw()));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Constants.java
index f5a7567b377..7fd6332bed2 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Constants.java
@@ -25,10 +25,10 @@ public class Constants {
public static final double kElevatorDrumRadius = Units.inchesToMeters(2.0);
public static final double kCarriageMass = 4.0; // kg
- public static final double kSetpointMeters = 0.75;
+ public static final double kSetpoint = 0.75; // m
// Encoder is reset to measure 0 at the bottom, so minimum height is 0.
- public static final double kMinElevatorHeightMeters = 0.0;
- public static final double kMaxElevatorHeightMeters = 1.25;
+ public static final double kMinElevatorHeight = 0.0; // m
+ public static final double kMaxElevatorHeight = 1.25; // m
// distance per pulse = (distance per revolution) / (pulses per revolution)
// = (Pi * D) / ppr
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
index e45ba060918..96f36b58df7 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java
@@ -31,7 +31,7 @@ public void simulationPeriodic() {
public void teleopPeriodic() {
if (m_joystick.getTrigger()) {
// Here, we set the constant setpoint of 0.75 meters.
- m_elevator.reachGoal(Constants.kSetpointMeters);
+ m_elevator.reachGoal(Constants.kSetpoint);
} else {
// Otherwise, we update the setpoint to 0.
m_elevator.reachGoal(0.0);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java
index 90378bd119a..ba31023120a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java
@@ -53,8 +53,8 @@ public class Elevator implements AutoCloseable {
Constants.kElevatorGearing,
Constants.kCarriageMass,
Constants.kElevatorDrumRadius,
- Constants.kMinElevatorHeightMeters,
- Constants.kMaxElevatorHeightMeters,
+ Constants.kMinElevatorHeight,
+ Constants.kMaxElevatorHeight,
true,
0,
0.01,
@@ -66,8 +66,7 @@ public class Elevator implements AutoCloseable {
private final Mechanism2d m_mech2d = new Mechanism2d(20, 50);
private final MechanismRoot2d m_mech2dRoot = m_mech2d.getRoot("Elevator Root", 10, 0);
private final MechanismLigament2d m_elevatorMech2d =
- m_mech2dRoot.append(
- new MechanismLigament2d("Elevator", m_elevatorSim.getPositionMeters(), 90));
+ m_mech2dRoot.append(new MechanismLigament2d("Elevator", m_elevatorSim.getPosition(), 90));
/** Subsystem constructor. */
public Elevator() {
@@ -88,10 +87,10 @@ public void simulationPeriodic() {
m_elevatorSim.update(0.020);
// Finally, we set our simulated encoder's readings and simulated battery voltage
- m_encoderSim.setDistance(m_elevatorSim.getPositionMeters());
+ m_encoderSim.setDistance(m_elevatorSim.getPosition());
// SimBattery estimates loaded battery voltages
RoboRioSim.setVInVoltage(
- BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDrawAmps()));
+ BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDraw()));
}
/**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java
index f9646e282a3..4b4dec06b3d 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java
@@ -15,9 +15,9 @@
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
- public static final int SHOT_VELOCITY = 200; // rpm
- public static final int TOLERANCE = 8; // rpm
- public static final int KICKER_THRESHOLD = 15; // mm
+ public static final double SHOT_VELOCITY = 200; // rpm
+ public static final double TOLERANCE = 8; // rpm
+ public static final double KICKER_THRESHOLD = 0.15; // m
private final PWMSparkMax m_shooter = new PWMSparkMax(0);
private final Encoder m_shooterEncoder = new Encoder(0, 1);
@@ -37,7 +37,7 @@ public Robot() {
m_controller.setTolerance(TOLERANCE);
BooleanEvent isBallAtKicker =
- new BooleanEvent(m_loop, () -> m_kickerSensor.getRangeMM() < KICKER_THRESHOLD);
+ new BooleanEvent(m_loop, () -> m_kickerSensor.getRange() < KICKER_THRESHOLD);
BooleanEvent intakeButton = new BooleanEvent(m_loop, () -> m_joystick.getRawButton(2));
// if the thumb button is held
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java
index 76fc4317594..9dae80f329a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/flywheelbangbangcontroller/Robot.java
@@ -96,6 +96,6 @@ public void simulationPeriodic() {
// simulation, and write the simulated velocities to our simulated encoder
m_flywheelSim.setInputVoltage(m_flywheelMotor.get() * RobotController.getInputVoltage());
m_flywheelSim.update(0.02);
- m_encoderSim.setRate(m_flywheelSim.getAngularVelocityRadPerSec());
+ m_encoderSim.setRate(m_flywheelSim.getAngularVelocity());
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
index 61cfce638ec..5105cbb90fb 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
@@ -95,23 +95,19 @@ public MecanumDriveWheelPositions getCurrentDistances() {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
- final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond);
- final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond);
- final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond);
- final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond);
+ final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeft);
+ final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRight);
+ final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeft);
+ final double backRightFeedforward = m_feedforward.calculate(speeds.rearRight);
final double frontLeftOutput =
- m_frontLeftPIDController.calculate(
- m_frontLeftEncoder.getRate(), speeds.frontLeftMetersPerSecond);
+ m_frontLeftPIDController.calculate(m_frontLeftEncoder.getRate(), speeds.frontLeft);
final double frontRightOutput =
- m_frontRightPIDController.calculate(
- m_frontRightEncoder.getRate(), speeds.frontRightMetersPerSecond);
+ m_frontRightPIDController.calculate(m_frontRightEncoder.getRate(), speeds.frontRight);
final double backLeftOutput =
- m_backLeftPIDController.calculate(
- m_backLeftEncoder.getRate(), speeds.rearLeftMetersPerSecond);
+ m_backLeftPIDController.calculate(m_backLeftEncoder.getRate(), speeds.rearLeft);
final double backRightOutput =
- m_backRightPIDController.calculate(
- m_backRightEncoder.getRate(), speeds.rearRightMetersPerSecond);
+ m_backRightPIDController.calculate(m_backRightEncoder.getRate(), speeds.rearRight);
m_frontLeftMotor.setVoltage(frontLeftOutput + frontLeftFeedforward);
m_frontRightMotor.setVoltage(frontRightOutput + frontRightFeedforward);
@@ -128,12 +124,12 @@ public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
public void drive(
- double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
+ double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds.toRobotRelativeSpeeds(m_gyro.getRotation2d());
}
- chassisSpeeds.discretize(periodSeconds);
+ chassisSpeeds.discretize(period);
var mecanumDriveWheelSpeeds = m_kinematics.toWheelSpeeds(chassisSpeeds);
mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
setSpeeds(mecanumDriveWheelSpeeds);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
index 19164dc29e8..80762194595 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
@@ -34,23 +34,23 @@ public static final class DriveConstants {
public static final boolean kFrontRightEncoderReversed = false;
public static final boolean kRearRightEncoderReversed = true;
- public static final double kTrackWidth = 0.5;
+ public static final double kTrackwidth = 0.5;
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = 0.7;
// Distance between centers of front and back wheels on robot
public static final MecanumDriveKinematics kDriveKinematics =
new MecanumDriveKinematics(
- new Translation2d(kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
+ new Translation2d(kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(kWheelBase / 2, -kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, -kTrackwidth / 2));
public static final int kEncoderCPR = 1024;
- public static final double kWheelDiameterMeters = 0.15;
+ public static final double kWheelDiameter = 0.15; // m
public static final double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * Math.PI) / kEncoderCPR;
+ (kWheelDiameter * Math.PI) / kEncoderCPR;
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
// These characterization values MUST be determined either experimentally or theoretically
@@ -71,10 +71,10 @@ public static final class OIConstants {
}
public static final class AutoConstants {
- public static final double kMaxSpeedMetersPerSecond = 3;
- public static final double kMaxAccelerationMetersPerSecondSquared = 3;
- public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
- public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
+ public static final double kMaxSpeed = 3; // m/s
+ public static final double kMaxAcceleration = 3; // m/s²
+ public static final double kMaxAngularSpeed = Math.PI; // rad/s
+ public static final double kMaxAngularAcceleration = Math.PI; // rad/s²
public static final double kPXController = 0.5;
public static final double kPYController = 0.5;
@@ -82,7 +82,6 @@ public static final class AutoConstants {
// Constraint for the motion profilied robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints =
- new TrapezoidProfile.Constraints(
- kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
+ new TrapezoidProfile.Constraints(kMaxAngularSpeed, kMaxAngularAcceleration);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
index 5ceb363806e..cf8e088ddb3 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/RobotContainer.java
@@ -80,9 +80,7 @@ private void configureButtonBindings() {
public Command getAutonomousCommand() {
// Create config for trajectory
TrajectoryConfig config =
- new TrajectoryConfig(
- AutoConstants.kMaxSpeedMetersPerSecond,
- AutoConstants.kMaxAccelerationMetersPerSecondSquared)
+ new TrajectoryConfig(AutoConstants.kMaxSpeed, AutoConstants.kMaxAcceleration)
// Add kinematics to ensure max speed is actually obeyed
.setKinematics(DriveConstants.kDriveKinematics);
@@ -111,7 +109,7 @@ public Command getAutonomousCommand() {
AutoConstants.kPThetaController, 0, 0, AutoConstants.kThetaControllerConstraints),
// Needed for normalizing wheel speeds
- AutoConstants.kMaxSpeedMetersPerSecond,
+ AutoConstants.kMaxSpeed,
// Velocity PID's
new PIDController(DriveConstants.kPFrontLeftVel, 0, 0),
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
index b3f9b3462ab..e9412ef0fcb 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
@@ -95,7 +95,7 @@ public void periodic() {
* @return The pose.
*/
public Pose2d getPose() {
- return m_odometry.getPoseMeters();
+ return m_odometry.getPose();
}
/**
@@ -126,10 +126,10 @@ public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelativ
/** Sets the front left drive MotorController to a voltage. */
public void setDriveMotorControllersVolts(MecanumDriveMotorVoltages volts) {
- m_frontLeft.setVoltage(volts.frontLeftVoltage);
- m_rearLeft.setVoltage(volts.rearLeftVoltage);
- m_frontRight.setVoltage(volts.frontRightVoltage);
- m_rearRight.setVoltage(volts.rearRightVoltage);
+ m_frontLeft.setVoltage(volts.frontLeft);
+ m_rearLeft.setVoltage(volts.rearLeft);
+ m_frontRight.setVoltage(volts.frontRight);
+ m_rearRight.setVoltage(volts.rearRight);
}
/** Resets the drive encoders to currently read a position of 0. */
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
index de481094486..5b67297e748 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
@@ -107,23 +107,19 @@ public MecanumDriveWheelPositions getCurrentDistances() {
* @param speeds The desired wheel speeds.
*/
public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
- final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeftMetersPerSecond);
- final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRightMetersPerSecond);
- final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeftMetersPerSecond);
- final double backRightFeedforward = m_feedforward.calculate(speeds.rearRightMetersPerSecond);
+ final double frontLeftFeedforward = m_feedforward.calculate(speeds.frontLeft);
+ final double frontRightFeedforward = m_feedforward.calculate(speeds.frontRight);
+ final double backLeftFeedforward = m_feedforward.calculate(speeds.rearLeft);
+ final double backRightFeedforward = m_feedforward.calculate(speeds.rearRight);
final double frontLeftOutput =
- m_frontLeftPIDController.calculate(
- m_frontLeftEncoder.getRate(), speeds.frontLeftMetersPerSecond);
+ m_frontLeftPIDController.calculate(m_frontLeftEncoder.getRate(), speeds.frontLeft);
final double frontRightOutput =
- m_frontRightPIDController.calculate(
- m_frontRightEncoder.getRate(), speeds.frontRightMetersPerSecond);
+ m_frontRightPIDController.calculate(m_frontRightEncoder.getRate(), speeds.frontRight);
final double backLeftOutput =
- m_backLeftPIDController.calculate(
- m_backLeftEncoder.getRate(), speeds.rearLeftMetersPerSecond);
+ m_backLeftPIDController.calculate(m_backLeftEncoder.getRate(), speeds.rearLeft);
final double backRightOutput =
- m_backRightPIDController.calculate(
- m_backRightEncoder.getRate(), speeds.rearRightMetersPerSecond);
+ m_backRightPIDController.calculate(m_backRightEncoder.getRate(), speeds.rearRight);
m_frontLeftMotor.setVoltage(frontLeftOutput + frontLeftFeedforward);
m_frontRightMotor.setVoltage(frontRightOutput + frontRightFeedforward);
@@ -140,12 +136,12 @@ public void setSpeeds(MecanumDriveWheelSpeeds speeds) {
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
public void drive(
- double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
+ double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds.toRobotRelativeSpeeds(m_poseEstimator.getEstimatedPosition().getRotation());
}
- chassisSpeeds.discretize(periodSeconds);
+ chassisSpeeds.discretize(period);
var mecanumDriveWheelSpeeds = m_kinematics.toWheelSpeeds(chassisSpeeds);
mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
setSpeeds(mecanumDriveWheelSpeeds);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java
index 65549bb1067..560e18f36b1 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java
@@ -20,10 +20,10 @@ public class Robot extends TimedRobot {
static final int kJoystickChannel = 3;
// The elevator can move 1.5 meters from top to bottom
- static final double kFullHeightMeters = 1.5;
+ static final double kFullHeight = 1.5;
- // Bottom, middle, and top elevator setpoints
- static final double[] kSetpointsMeters = {0.2, 0.8, 1.4};
+ // Bottom, middle, and top elevator setpoints in meters
+ static final double[] kSetpoints = {0.2, 0.8, 1.4};
// proportional, integral, and derivative speed constants
// DANGER: when tuning PID constants, high/inappropriate values for kP, kI,
@@ -35,7 +35,7 @@ public class Robot extends TimedRobot {
private final PIDController m_pidController = new PIDController(kP, kI, kD);
// Scaling is handled internally
private final AnalogPotentiometer m_potentiometer =
- new AnalogPotentiometer(kPotChannel, kFullHeightMeters);
+ new AnalogPotentiometer(kPotChannel, kFullHeight);
private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(kMotorChannel);
private final Joystick m_joystick = new Joystick(kJoystickChannel);
@@ -45,7 +45,7 @@ public class Robot extends TimedRobot {
public void teleopInit() {
// Move to the bottom setpoint when teleop starts
m_index = 0;
- m_pidController.setSetpoint(kSetpointsMeters[m_index]);
+ m_pidController.setSetpoint(kSetpoints[m_index]);
}
@Override
@@ -62,9 +62,9 @@ public void teleopPeriodic() {
// when the button is pressed once, the selected elevator setpoint is incremented
if (m_joystick.getTriggerPressed()) {
// index of the elevator setpoint wraps around.
- m_index = (m_index + 1) % kSetpointsMeters.length;
+ m_index = (m_index + 1) % kSetpoints.length;
System.out.println("m_index = " + m_index);
- m_pidController.setSetpoint(kSetpointsMeters[m_index]);
+ m_pidController.setSetpoint(kSetpoints[m_index]);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java
index e0bdb757ba0..86ce61da9f9 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/Constants.java
@@ -27,10 +27,10 @@ public static final class DriveConstants {
public static final boolean kRightEncoderReversed = true;
public static final int kEncoderCPR = 1024;
- public static final double kWheelDiameterMeters = Units.inchesToMeters(6);
+ public static final double kWheelDiameter = Units.inchesToMeters(6);
public static final double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * Math.PI) / kEncoderCPR;
+ (kWheelDiameter * Math.PI) / kEncoderCPR;
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
// These values MUST be determined either experimentally or theoretically for *your* robot's
@@ -88,8 +88,8 @@ public static final class StorageConstants {
}
public static final class AutoConstants {
- public static final double kTimeoutSeconds = 3;
- public static final double kDriveDistanceMeters = 2;
+ public static final double kTimeout = 3;
+ public static final double kDriveDistance = 2; // m
public static final double kDriveSpeed = 0.5;
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java
index a4273a481ae..750279b0d2f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java
@@ -87,7 +87,7 @@ public void configureBindings() {
public Command getAutonomousCommand() {
// Drive forward for 2 meters at half speed with a 3 second timeout
return m_drive
- .driveDistanceCommand(AutoConstants.kDriveDistanceMeters, AutoConstants.kDriveSpeed)
- .withTimeout(AutoConstants.kTimeoutSeconds);
+ .driveDistanceCommand(AutoConstants.kDriveDistance, AutoConstants.kDriveSpeed)
+ .withTimeout(AutoConstants.kTimeout);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java
index dbb234a8d0a..f1c45d29545 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java
@@ -105,10 +105,10 @@ public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) {
/**
* Returns a command that drives the robot forward a specified distance at a specified speed.
*
- * @param distanceMeters The distance to drive forward in meters
+ * @param distance The distance to drive forward in meters
* @param speed The fraction of max speed at which to drive
*/
- public Command driveDistanceCommand(double distanceMeters, double speed) {
+ public Command driveDistanceCommand(double distance, double speed) {
return runOnce(
() -> {
// Reset encoders at the start of the command
@@ -119,9 +119,7 @@ public Command driveDistanceCommand(double distanceMeters, double speed) {
.andThen(run(() -> m_drive.arcadeDrive(speed, 0)))
// End command when we've traveled the specified distance
.until(
- () ->
- Math.max(m_leftEncoder.getDistance(), m_rightEncoder.getDistance())
- >= distanceMeters)
+ () -> Math.max(m_leftEncoder.getDistance(), m_rightEncoder.getDistance()) >= distance)
// Stop the drive when the command ends
.finallyDo(interrupted -> m_drive.stopMotor());
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
index d0d1ed4dcdc..18130b33769 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
@@ -31,7 +31,7 @@ public class Drivetrain {
// 1/2 rotation per second.
public static final double kMaxAngularSpeed = Math.PI;
- private static final double kTrackWidth = 0.381 * 2;
+ private static final double kTrackwidth = 0.381 * 2;
private static final double kWheelRadius = 0.0508;
private static final int kEncoderResolution = -4096;
@@ -49,7 +49,7 @@ public class Drivetrain {
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final DifferentialDriveKinematics m_kinematics =
- new DifferentialDriveKinematics(kTrackWidth);
+ new DifferentialDriveKinematics(kTrackwidth);
private final DifferentialDriveOdometry m_odometry =
new DifferentialDriveOdometry(
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
@@ -67,7 +67,7 @@ public class Drivetrain {
LinearSystemId.identifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3);
private final DifferentialDrivetrainSim m_drivetrainSimulator =
new DifferentialDrivetrainSim(
- m_drivetrainSystem, DCMotor.getCIM(2), 8, kTrackWidth, kWheelRadius, null);
+ m_drivetrainSystem, DCMotor.getCIM(2), 8, kTrackwidth, kWheelRadius, null);
/** Subsystem constructor. */
public Drivetrain() {
@@ -94,12 +94,10 @@ public Drivetrain() {
/** Sets speeds to the drivetrain motors. */
public void setSpeeds(DifferentialDriveWheelSpeeds speeds) {
- final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
- final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
- double leftOutput =
- m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
- double rightOutput =
- m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
+ final double leftFeedforward = m_feedforward.calculate(speeds.left);
+ final double rightFeedforward = m_feedforward.calculate(speeds.right);
+ double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.left);
+ double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.right);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
@@ -130,7 +128,7 @@ public void resetOdometry(Pose2d pose) {
/** Check the current robot pose. */
public Pose2d getPose() {
- return m_odometry.getPoseMeters();
+ return m_odometry.getPose();
}
/** Update our simulation. This should be run every robot loop in simulation. */
@@ -144,16 +142,16 @@ public void simulationPeriodic() {
m_rightLeader.get() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
- m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
- m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocityMetersPerSecond());
- m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPositionMeters());
- m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocityMetersPerSecond());
+ m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPosition());
+ m_leftEncoderSim.setRate(m_drivetrainSimulator.getLeftVelocity());
+ m_rightEncoderSim.setDistance(m_drivetrainSimulator.getRightPosition());
+ m_rightEncoderSim.setRate(m_drivetrainSimulator.getRightVelocity());
m_gyroSim.setAngle(-m_drivetrainSimulator.getHeading().getDegrees());
}
/** Update odometry - this should be run every robot loop. */
public void periodic() {
updateOdometry();
- m_fieldSim.setRobotPose(m_odometry.getPoseMeters());
+ m_fieldSim.setRobotPose(m_odometry.getPose());
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
index 85953c63579..d8471b2c49a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
@@ -56,7 +56,7 @@ public void autonomousPeriodic() {
double elapsed = m_timer.get();
Trajectory.State reference = m_trajectory.sample(elapsed);
ChassisSpeeds speeds = m_feedback.calculate(m_drive.getPose(), reference);
- m_drive.drive(speeds.vxMetersPerSecond, speeds.omegaRadiansPerSecond);
+ m_drive.drive(speeds.vx, speeds.omega);
}
@Override
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
index f622259b494..2b93f5b0397 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
@@ -56,12 +56,12 @@ public Drivetrain() {
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
public void drive(
- double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
+ double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds.toRobotRelativeSpeeds(m_gyro.getRotation2d());
}
- chassisSpeeds.discretize(periodSeconds);
+ chassisSpeeds.discretize(period);
var swerveModuleStates = m_kinematics.toWheelSpeeds(chassisSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
m_frontLeft.setDesiredState(swerveModuleStates[0]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
index b57ba6e5eae..1590dfaa805 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
@@ -121,9 +121,9 @@ public void setDesiredState(SwerveModuleState desiredState) {
// Calculate the drive output from the drive PID controller.
final double driveOutput =
- m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
+ m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speed);
- final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speedMetersPerSecond);
+ final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speed);
// Calculate the turning motor output from the turning PID controller.
final double turnOutput =
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
index acdaa388594..3a13b717792 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
@@ -52,16 +52,16 @@ public static final class DriveConstants {
// If you call DriveSubsystem.drive() with a different period make sure to update this.
public static final double kDrivePeriod = TimedRobot.kDefaultPeriod;
- public static final double kTrackWidth = 0.5;
+ public static final double kTrackwidth = 0.5;
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = 0.7;
// Distance between front and back wheels on robot
public static final SwerveDriveKinematics kDriveKinematics =
new SwerveDriveKinematics(
- new Translation2d(kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
- new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
+ new Translation2d(kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(kWheelBase / 2, -kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, kTrackwidth / 2),
+ new Translation2d(-kWheelBase / 2, -kTrackwidth / 2));
public static final boolean kGyroReversed = false;
@@ -69,22 +69,22 @@ public static final class DriveConstants {
// These characterization values MUST be determined either experimentally or theoretically
// for *your* robot's drive.
// The SysId tool provides a convenient method for obtaining these values for your robot.
- public static final double ksVolts = 1;
- public static final double kvVoltSecondsPerMeter = 0.8;
- public static final double kaVoltSecondsSquaredPerMeter = 0.15;
+ public static final double ks = 1; // V
+ public static final double kv = 0.8; // V/(m/s)
+ public static final double ka = 0.15; // V/(m/s²)
- public static final double kMaxSpeedMetersPerSecond = 3;
+ public static final double kMaxSpeed = 3; // m/s
}
public static final class ModuleConstants {
- public static final double kMaxModuleAngularSpeedRadiansPerSecond = 2 * Math.PI;
- public static final double kMaxModuleAngularAccelerationRadiansPerSecondSquared = 2 * Math.PI;
+ public static final double kMaxModuleAngularSpeed = 2 * Math.PI; // rad/s
+ public static final double kMaxModuleAngularAcceleration = 2 * Math.PI; // rad/s²
public static final int kEncoderCPR = 1024;
- public static final double kWheelDiameterMeters = 0.15;
+ public static final double kWheelDiameter = 0.15; // m
public static final double kDriveEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * Math.PI) / kEncoderCPR;
+ (kWheelDiameter * Math.PI) / kEncoderCPR;
public static final double kTurningEncoderDistancePerPulse =
// Assumes the encoders are on a 1:1 reduction with the module shaft.
@@ -100,10 +100,10 @@ public static final class OIConstants {
}
public static final class AutoConstants {
- public static final double kMaxSpeedMetersPerSecond = 3;
- public static final double kMaxAccelerationMetersPerSecondSquared = 3;
- public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
- public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
+ public static final double kMaxSpeed = 3; // m/s
+ public static final double kMaxAcceleration = 3; // m/s²
+ public static final double kMaxAngularSpeed = Math.PI; // rad/s
+ public static final double kMaxAngularAcceleration = Math.PI; // rad/s²
public static final double kPXController = 1;
public static final double kPYController = 1;
@@ -111,7 +111,6 @@ public static final class AutoConstants {
// Constraint for the motion profiled robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints =
- new TrapezoidProfile.Constraints(
- kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
+ new TrapezoidProfile.Constraints(kMaxAngularSpeed, kMaxAngularAcceleration);
}
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
index f2641890a6d..b729de42bb8 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
@@ -54,10 +54,9 @@ public RobotContainer() {
// Multiply by max speed to map the joystick unitless inputs to actual units.
// This will map the [-1, 1] to [max speed backwards, max speed forwards],
// converting them to actual units.
- m_driverController.getLeftY() * DriveConstants.kMaxSpeedMetersPerSecond,
- m_driverController.getLeftX() * DriveConstants.kMaxSpeedMetersPerSecond,
- m_driverController.getRightX()
- * ModuleConstants.kMaxModuleAngularSpeedRadiansPerSecond,
+ m_driverController.getLeftY() * DriveConstants.kMaxSpeed,
+ m_driverController.getLeftX() * DriveConstants.kMaxSpeed,
+ m_driverController.getRightX() * ModuleConstants.kMaxModuleAngularSpeed,
false),
m_robotDrive));
}
@@ -78,9 +77,7 @@ private void configureButtonBindings() {}
public Command getAutonomousCommand() {
// Create config for trajectory
TrajectoryConfig config =
- new TrajectoryConfig(
- AutoConstants.kMaxSpeedMetersPerSecond,
- AutoConstants.kMaxAccelerationMetersPerSecondSquared)
+ new TrajectoryConfig(AutoConstants.kMaxSpeed, AutoConstants.kMaxAcceleration)
// Add kinematics to ensure max speed is actually obeyed
.setKinematics(DriveConstants.kDriveKinematics);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
index c950e4c7c53..de934c4a15e 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
@@ -89,7 +89,7 @@ public void periodic() {
* @return The pose.
*/
public Pose2d getPose() {
- return m_odometry.getPoseMeters();
+ return m_odometry.getPose();
}
/**
@@ -124,8 +124,7 @@ public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelativ
}
chassisSpeeds.discretize(DriveConstants.kDrivePeriod);
var swerveModuleStates = DriveConstants.kDriveKinematics.toWheelSpeeds(chassisSpeeds);
- SwerveDriveKinematics.desaturateWheelSpeeds(
- swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond);
+ SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, DriveConstants.kMaxSpeed);
m_frontLeft.setDesiredState(swerveModuleStates[0]);
m_frontRight.setDesiredState(swerveModuleStates[1]);
m_rearLeft.setDesiredState(swerveModuleStates[2]);
@@ -138,8 +137,7 @@ public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelativ
* @param desiredStates The desired SwerveModule states.
*/
public void setModuleStates(SwerveModuleState[] desiredStates) {
- SwerveDriveKinematics.desaturateWheelSpeeds(
- desiredStates, DriveConstants.kMaxSpeedMetersPerSecond);
+ SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, DriveConstants.kMaxSpeed);
m_frontLeft.setDesiredState(desiredStates[0]);
m_frontRight.setDesiredState(desiredStates[1]);
m_rearLeft.setDesiredState(desiredStates[2]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
index 1a032d273fa..0ee79e7d029 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
@@ -31,8 +31,8 @@ public class SwerveModule {
0,
0,
new TrapezoidProfile.Constraints(
- ModuleConstants.kMaxModuleAngularSpeedRadiansPerSecond,
- ModuleConstants.kMaxModuleAngularAccelerationRadiansPerSecondSquared));
+ ModuleConstants.kMaxModuleAngularSpeed,
+ ModuleConstants.kMaxModuleAngularAcceleration));
/**
* Constructs a SwerveModule.
@@ -117,7 +117,7 @@ public void setDesiredState(SwerveModuleState desiredState) {
// Calculate the drive output from the drive PID controller.
final double driveOutput =
- m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
+ m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speed);
// Calculate the turning motor output from the turning PID controller.
final double turnOutput =
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
index a28dfcacc28..a73b94d59e1 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
@@ -68,12 +68,12 @@ public Drivetrain() {
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
public void drive(
- double xSpeed, double ySpeed, double rot, boolean fieldRelative, double periodSeconds) {
+ double xSpeed, double ySpeed, double rot, boolean fieldRelative, double period) {
var chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, rot);
if (fieldRelative) {
chassisSpeeds.toRobotRelativeSpeeds(m_poseEstimator.getEstimatedPosition().getRotation());
}
- chassisSpeeds.discretize(periodSeconds);
+ chassisSpeeds.discretize(period);
var swerveModuleStates = m_kinematics.toWheelSpeeds(chassisSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
m_frontLeft.setDesiredState(swerveModuleStates[0]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
index e8af157d37b..45111f1275a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java
@@ -120,9 +120,9 @@ public void setDesiredState(SwerveModuleState desiredState) {
// Calculate the drive output from the drive PID controller.
final double driveOutput =
- m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speedMetersPerSecond);
+ m_drivePIDController.calculate(m_driveEncoder.getRate(), desiredState.speed);
- final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speedMetersPerSecond);
+ final double driveFeedforward = m_driveFeedforward.calculate(desiredState.speed);
// Calculate the turning motor output from the turning PID controller.
final double turnOutput =
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysidroutine/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysidroutine/Constants.java
index 7e45d022479..b6d441347c5 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysidroutine/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/sysidroutine/Constants.java
@@ -27,10 +27,10 @@ public static final class DriveConstants {
public static final boolean kRightEncoderReversed = true;
public static final int kEncoderCPR = 1024;
- public static final double kWheelDiameterMeters = Units.inchesToMeters(6);
+ public static final double kWheelDiameter = Units.inchesToMeters(6);
public static final double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
- (kWheelDiameterMeters * Math.PI) / kEncoderCPR;
+ (kWheelDiameter * Math.PI) / kEncoderCPR;
}
public static final class ShooterConstants {
@@ -73,8 +73,8 @@ public static final class StorageConstants {
}
public static final class AutoConstants {
- public static final double kTimeoutSeconds = 3;
- public static final double kDriveDistanceMeters = 2;
+ public static final double kTimeout = 3;
+ public static final double kDriveDistance = 2; // m
public static final double kDriveSpeed = 0.5;
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java
index 602e58abe5b..7d0b375e7aa 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java
@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.ultrasonic;
+import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Ultrasonic;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
@@ -26,14 +27,12 @@ public Robot() {
@Override
public void teleopPeriodic() {
- // We can read the distance in millimeters
- double distanceMillimeters = m_rangeFinder.getRangeMM();
- // ... or in inches
- double distanceInches = m_rangeFinder.getRangeInches();
+ // Read distance in meters
+ double distance = m_rangeFinder.getRange();
// We can also publish the data itself periodically
- SmartDashboard.putNumber("Distance[mm]", distanceMillimeters);
- SmartDashboard.putNumber("Distance[inch]", distanceInches);
+ SmartDashboard.putNumber("Distance[m]", distance);
+ SmartDashboard.putNumber("Distance[inch]", Units.metersToInches(distance));
}
@Override
@@ -48,8 +47,8 @@ public void testInit() {
public void testPeriodic() {
if (m_rangeFinder.isRangeValid()) {
// Data is valid, publish it
- SmartDashboard.putNumber("Distance[mm]", m_rangeFinder.getRangeMM());
- SmartDashboard.putNumber("Distance[inch]", m_rangeFinder.getRangeInches());
+ SmartDashboard.putNumber("Distance[m]", m_rangeFinder.getRange());
+ SmartDashboard.putNumber("Distance[inch]", Units.metersToInches(m_rangeFinder.getRange()));
// Ping for next measurement
m_rangeFinder.ping();
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java
index 33681d00859..a49b69c272c 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java
@@ -19,10 +19,10 @@
public class Robot extends TimedRobot {
// distance the robot wants to stay from an object
// (one meter)
- static final double kHoldDistanceMillimeters = 1.0e3;
+ static final double kHoldDistance = 1.0; // m
// proportional speed constant
- private static final double kP = 0.001;
+ private static final double kP = 1.0;
// integral speed constant
private static final double kI = 0.0;
// derivative speed constant
@@ -53,12 +53,12 @@ public Robot() {
@Override
public void autonomousInit() {
// Set setpoint of the pid controller
- m_pidController.setSetpoint(kHoldDistanceMillimeters);
+ m_pidController.setSetpoint(kHoldDistance);
}
@Override
public void autonomousPeriodic() {
- double measurement = m_ultrasonic.getRangeMM();
+ double measurement = m_ultrasonic.getRange();
double filteredMeasurement = m_filter.calculate(measurement);
double pidOutput = m_pidController.calculate(filteredMeasurement);
diff --git a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/ElevatorSimulationTest.java b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/ElevatorSimulationTest.java
index 7faeec68f33..d7074a0fd99 100644
--- a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/ElevatorSimulationTest.java
+++ b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/ElevatorSimulationTest.java
@@ -88,12 +88,12 @@ void teleopTest() {
// advance 75 timesteps
SimHooks.stepTiming(1.5);
- assertEquals(Constants.kSetpointMeters, m_encoderSim.getDistance(), 0.05);
+ assertEquals(Constants.kSetpoint, m_encoderSim.getDistance(), 0.05);
// advance 25 timesteps to see setpoint is held.
SimHooks.stepTiming(0.5);
- assertEquals(Constants.kSetpointMeters, m_encoderSim.getDistance(), 0.05);
+ assertEquals(Constants.kSetpoint, m_encoderSim.getDistance(), 0.05);
}
{
@@ -115,12 +115,12 @@ void teleopTest() {
// advance 75 timesteps
SimHooks.stepTiming(1.5);
- assertEquals(Constants.kSetpointMeters, m_encoderSim.getDistance(), 0.05);
+ assertEquals(Constants.kSetpoint, m_encoderSim.getDistance(), 0.05);
// advance 25 timesteps to see setpoint is held.
SimHooks.stepTiming(0.5);
- assertEquals(Constants.kSetpointMeters, m_encoderSim.getDistance(), 0.05);
+ assertEquals(Constants.kSetpoint, m_encoderSim.getDistance(), 0.05);
}
{
diff --git a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/potentiometerpid/PotentiometerPIDTest.java b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/potentiometerpid/PotentiometerPIDTest.java
index 8a3d92b8e66..6fe3cc413e6 100644
--- a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/potentiometerpid/PotentiometerPIDTest.java
+++ b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/potentiometerpid/PotentiometerPIDTest.java
@@ -53,7 +53,7 @@ void startThread() {
kCarriageMassKg,
kElevatorDrumRadius,
0.0,
- Robot.kFullHeightMeters,
+ Robot.kFullHeight,
true,
0);
m_analogSim = new AnalogInputSim(Robot.kPotChannel);
@@ -74,7 +74,7 @@ void startThread() {
*/
m_analogSim.setVoltage(
RobotController.getVoltage5V()
- * (m_elevatorSim.getPositionMeters() / Robot.kFullHeightMeters));
+ * (m_elevatorSim.getPosition() / Robot.kFullHeight));
});
m_thread.start();
@@ -113,7 +113,7 @@ void teleopTest() {
// advance 50 timesteps
SimHooks.stepTiming(1);
- assertEquals(Robot.kSetpointsMeters[0], m_elevatorSim.getPositionMeters(), 0.1);
+ assertEquals(Robot.kSetpoints[0], m_elevatorSim.getPosition(), 0.1);
}
// second setpoint
@@ -125,7 +125,7 @@ void teleopTest() {
// advance 50 timesteps
SimHooks.stepTiming(1);
- assertEquals(Robot.kSetpointsMeters[1], m_elevatorSim.getPositionMeters(), 0.1);
+ assertEquals(Robot.kSetpoints[1], m_elevatorSim.getPosition(), 0.1);
}
// we need to unpress the button
@@ -146,7 +146,7 @@ void teleopTest() {
// advance 50 timesteps
SimHooks.stepTiming(1);
- assertEquals(Robot.kSetpointsMeters[2], m_elevatorSim.getPositionMeters(), 0.1);
+ assertEquals(Robot.kSetpoints[2], m_elevatorSim.getPosition(), 0.1);
}
// we need to unpress the button
@@ -167,7 +167,7 @@ void teleopTest() {
// advance 60 timesteps
SimHooks.stepTiming(1.2);
- assertEquals(Robot.kSetpointsMeters[0], m_elevatorSim.getPositionMeters(), 0.1);
+ assertEquals(Robot.kSetpoints[0], m_elevatorSim.getPosition(), 0.1);
}
}
}
diff --git a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/UltrasonicPIDTest.java b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/UltrasonicPIDTest.java
index f0a27b8f9c0..9c5cf5360d2 100644
--- a/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/UltrasonicPIDTest.java
+++ b/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/UltrasonicPIDTest.java
@@ -27,12 +27,12 @@
class UltrasonicPIDTest {
private final DCMotor m_gearbox = DCMotor.getFalcon500(2);
private static final double kGearing = KitbotGearing.k10p71.value;
- public static final double kvVoltSecondsPerMeter = 1.98;
- public static final double kaVoltSecondsSquaredPerMeter = 0.2;
- private static final double kvVoltSecondsPerRadian = 1.5;
- private static final double kaVoltSecondsSquaredPerRadian = 0.3;
- private static final double kWheelDiameterMeters = 0.15;
- private static final double kTrackwidthMeters = 0.7;
+ public static final double kvLinear = 1.98; // V/(m/s)
+ public static final double kaLinear = 0.2; // V/m/s²)
+ private static final double kvAngular = 1.5; // V/(rad/s)
+ private static final double kaAngular = 0.3; // V/(rad/s²)
+ private static final double kWheelDiameter = 0.15; // m
+ private static final double kTrackwidth = 0.7; // m
private Robot m_robot;
private Thread m_thread;
@@ -46,7 +46,7 @@ class UltrasonicPIDTest {
// distance between the robot's starting position and the object
// we will update this in a moment
private double m_startToObject = Double.POSITIVE_INFINITY;
- private double m_distanceMM;
+ private double m_distance; // m
// We're not using @BeforeEach so m_startToObject gets initialized properly
private void startThread() {
@@ -57,15 +57,11 @@ private void startThread() {
m_thread = new Thread(m_robot::startCompetition);
m_driveSim =
new DifferentialDrivetrainSim(
- LinearSystemId.identifyDrivetrainSystem(
- kvVoltSecondsPerMeter,
- kaVoltSecondsSquaredPerMeter,
- kvVoltSecondsPerRadian,
- kaVoltSecondsSquaredPerRadian),
+ LinearSystemId.identifyDrivetrainSystem(kvLinear, kaLinear, kvAngular, kaAngular),
m_gearbox,
kGearing,
- kTrackwidthMeters,
- kWheelDiameterMeters / 2.0,
+ kTrackwidth,
+ kWheelDiameter / 2.0,
null);
m_ultrasonicSim = new UltrasonicSim(Robot.kUltrasonicPingPort, Robot.kUltrasonicEchoPort);
m_leftMotorSim = new PWMSim(Robot.kLeftMotorPort);
@@ -80,10 +76,10 @@ private void startThread() {
m_driveSim.update(0.02);
double startingDistance = m_startToObject;
- double range = m_driveSim.getLeftPositionMeters() - startingDistance;
+ double range = m_driveSim.getLeftPosition() - startingDistance;
- m_ultrasonicSim.setRangeMeters(range);
- m_distanceMM = range * 1.0e3;
+ m_ultrasonicSim.setRange(range);
+ m_distance = range;
});
m_thread.start();
@@ -128,7 +124,7 @@ void autoTest(double distance) {
{
SimHooks.stepTiming(5.0);
- assertEquals(Robot.kHoldDistanceMillimeters, m_distanceMM, 10.0);
+ assertEquals(Robot.kHoldDistance, m_distance, 0.01);
}
}
}
diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
index 5494f0b6752..2d2737b7d6d 100644
--- a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
+++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java
@@ -529,9 +529,9 @@ public static final class ProtobufDifferentialDriveKinematics extends ProtoMessa
private static final long serialVersionUID = 0L;
/**
- * optional double track_width = 1;
+ * optional double trackwidth = 1;
*/
- private double trackWidth;
+ private double trackwidth;
private ProtobufDifferentialDriveKinematics() {
}
@@ -544,39 +544,39 @@ public static ProtobufDifferentialDriveKinematics newInstance() {
}
/**
- * optional double track_width = 1;
- * @return whether the trackWidth field is set
+ * optional double trackwidth = 1;
+ * @return whether the trackwidth field is set
*/
- public boolean hasTrackWidth() {
+ public boolean hasTrackwidth() {
return (bitField0_ & 0x00000001) != 0;
}
/**
- * optional double track_width = 1;
+ * optional double trackwidth = 1;
* @return this
*/
- public ProtobufDifferentialDriveKinematics clearTrackWidth() {
+ public ProtobufDifferentialDriveKinematics clearTrackwidth() {
bitField0_ &= ~0x00000001;
- trackWidth = 0D;
+ trackwidth = 0D;
return this;
}
/**
- * optional double track_width = 1;
- * @return the trackWidth
+ * optional double trackwidth = 1;
+ * @return the trackwidth
*/
- public double getTrackWidth() {
- return trackWidth;
+ public double getTrackwidth() {
+ return trackwidth;
}
/**
- * optional double track_width = 1;
- * @param value the trackWidth to set
+ * optional double trackwidth = 1;
+ * @param value the trackwidth to set
* @return this
*/
- public ProtobufDifferentialDriveKinematics setTrackWidth(final double value) {
+ public ProtobufDifferentialDriveKinematics setTrackwidth(final double value) {
bitField0_ |= 0x00000001;
- trackWidth = value;
+ trackwidth = value;
return this;
}
@@ -586,7 +586,7 @@ public ProtobufDifferentialDriveKinematics copyFrom(
cachedSize = other.cachedSize;
if ((bitField0_ | other.bitField0_) != 0) {
bitField0_ = other.bitField0_;
- trackWidth = other.trackWidth;
+ trackwidth = other.trackwidth;
}
return this;
}
@@ -598,8 +598,8 @@ public ProtobufDifferentialDriveKinematics mergeFrom(
return this;
}
cachedSize = -1;
- if (other.hasTrackWidth()) {
- setTrackWidth(other.trackWidth);
+ if (other.hasTracwidth()) {
+ setTrackwidth(other.trackwidth);
}
return this;
}
@@ -611,7 +611,7 @@ public ProtobufDifferentialDriveKinematics clear() {
}
cachedSize = -1;
bitField0_ = 0;
- trackWidth = 0D;
+ trackwidth = 0D;
return this;
}
@@ -635,14 +635,14 @@ public boolean equals(Object o) {
}
ProtobufDifferentialDriveKinematics other = (ProtobufDifferentialDriveKinematics) o;
return bitField0_ == other.bitField0_
- && (!hasTrackWidth() || ProtoUtil.isEqual(trackWidth, other.trackWidth));
+ && (!hasTrackwidth() || ProtoUtil.isEqual(trackwidth, other.trackwidth));
}
@Override
public void writeTo(final ProtoSink output) throws IOException {
if ((bitField0_ & 0x00000001) != 0) {
output.writeRawByte((byte) 9);
- output.writeDoubleNoTag(trackWidth);
+ output.writeDoubleNoTag(trackwidth);
}
}
@@ -664,8 +664,8 @@ public ProtobufDifferentialDriveKinematics mergeFrom(final ProtoSource input) th
while (true) {
switch (tag) {
case 9: {
- // trackWidth
- trackWidth = input.readDouble();
+ // trackwidth
+ trackwidth = input.readDouble();
bitField0_ |= 0x00000001;
tag = input.readTag();
if (tag != 0) {
@@ -690,7 +690,7 @@ public ProtobufDifferentialDriveKinematics mergeFrom(final ProtoSource input) th
public void writeTo(final JsonSink output) throws IOException {
output.beginObject();
if ((bitField0_ & 0x00000001) != 0) {
- output.writeDouble(FieldNames.trackWidth, trackWidth);
+ output.writeDouble(FieldNames.trackwidth, trackwidth);
}
output.endObject();
}
@@ -705,9 +705,9 @@ public ProtobufDifferentialDriveKinematics mergeFrom(final JsonSource input) thr
switch (input.readFieldHash()) {
case 1152213819:
case 1600986578: {
- if (input.isAtField(FieldNames.trackWidth)) {
+ if (input.isAtField(FieldNames.trackwidth)) {
if (!input.trySkipNullValue()) {
- trackWidth = input.readDouble();
+ trackwidth = input.readDouble();
bitField0_ |= 0x00000001;
}
} else {
@@ -777,7 +777,7 @@ public ProtobufDifferentialDriveKinematics create() {
* Contains name constants used for serializing JSON
*/
static class FieldNames {
- static final FieldName trackWidth = FieldName.forField("trackWidth", "track_width");
+ static final FieldName trackwidth = FieldName.forField("trackwidth", "trackwidth");
}
}
diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
index e55103ffb80..e45f716d1c8 100644
--- a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
+++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h
@@ -31,7 +31,7 @@ typedef struct _wpi_proto_ProtobufDifferentialDriveKinematics {
static std::string_view msg_name(void) noexcept;
static pb_filedesc_t file_descriptor(void) noexcept;
- double track_width;
+ double trackwidth;
} wpi_proto_ProtobufDifferentialDriveKinematics;
typedef struct _wpi_proto_ProtobufDifferentialDriveWheelSpeeds {
@@ -151,7 +151,7 @@ typedef struct _wpi_proto_ProtobufSwerveModuleState {
#define wpi_proto_ProtobufChassisSpeeds_vx_tag 1
#define wpi_proto_ProtobufChassisSpeeds_vy_tag 2
#define wpi_proto_ProtobufChassisSpeeds_omega_tag 3
-#define wpi_proto_ProtobufDifferentialDriveKinematics_track_width_tag 1
+#define wpi_proto_ProtobufDifferentialDriveKinematics_trackwidth_tag 1
#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_left_tag 1
#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_right_tag 2
#define wpi_proto_ProtobufDifferentialDriveWheelPositions_left_tag 1
@@ -187,7 +187,7 @@ X(a, STATIC, SINGULAR, DOUBLE, omega, 3)
#define wpi_proto_ProtobufChassisSpeeds_DEFAULT NULL
#define wpi_proto_ProtobufDifferentialDriveKinematics_FIELDLIST(X, a) \
-X(a, STATIC, SINGULAR, DOUBLE, track_width, 1)
+X(a, STATIC, SINGULAR, DOUBLE, trackwidth, 1)
#define wpi_proto_ProtobufDifferentialDriveKinematics_CALLBACK NULL
#define wpi_proto_ProtobufDifferentialDriveKinematics_DEFAULT NULL
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
index 2f9ffe6ce72..544ce65fd9b 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
@@ -44,12 +44,12 @@ public class ArmFeedforward implements ProtobufSerializable, StructSerializable
* @param kg The gravity gain in volts.
* @param kv The velocity gain in V/(rad/s).
* @param ka The acceleration gain in V/(rad/s²).
- * @param dtSeconds The period in seconds.
+ * @param dt The period in seconds.
* @throws IllegalArgumentException for kv < zero.
* @throws IllegalArgumentException for ka < zero.
* @throws IllegalArgumentException for period ≤ zero.
*/
- public ArmFeedforward(double ks, double kg, double kv, double ka, double dtSeconds) {
+ public ArmFeedforward(double ks, double kg, double kv, double ka, double dt) {
this.ks = ks;
this.kg = kg;
this.kv = kv;
@@ -60,11 +60,10 @@ public ArmFeedforward(double ks, double kg, double kv, double ka, double dtSecon
if (ka < 0.0) {
throw new IllegalArgumentException("ka must be a non-negative number, got " + ka + "!");
}
- if (dtSeconds <= 0.0) {
- throw new IllegalArgumentException(
- "period must be a positive number, got " + dtSeconds + "!");
+ if (dt <= 0.0) {
+ throw new IllegalArgumentException("period must be a positive number, got " + dt + "!");
}
- m_dt = dtSeconds;
+ m_dt = dt;
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
index 9b14542207f..ca541b103a3 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java
@@ -54,14 +54,14 @@ public class ControlAffinePlantInversionFeedforward states,
Nat inputs,
BiFunction, Matrix, Matrix> f,
- double dtSeconds) {
- this.m_dt = dtSeconds;
+ double dt) {
+ this.m_dt = dt;
this.m_f = f;
this.m_inputs = inputs;
@@ -84,15 +84,15 @@ public ControlAffinePlantInversionFeedforward(
* @param f A vector-valued function of x, the state, that returns the derivative of the state
* vector.
* @param B Continuous input matrix of the plant being controlled.
- * @param dtSeconds The timestep between calls of calculate().
+ * @param dt The timestep between calls of calculate() in seconds.
*/
public ControlAffinePlantInversionFeedforward(
Nat states,
Nat inputs,
Function, Matrix> f,
Matrix B,
- double dtSeconds) {
- this.m_dt = dtSeconds;
+ double dt) {
+ this.m_dt = dt;
this.m_inputs = inputs;
this.m_f = (x, u) -> f.apply(x);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java
index 15be9f62f9b..549adbd4a24 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveFeedforward.java
@@ -71,7 +71,7 @@ public DifferentialDriveFeedforward(
* @param currentRightVelocity The current right velocity of the differential drive in
* meters/second.
* @param nextRightVelocity The next right velocity of the differential drive in meters/second.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @return A DifferentialDriveWheelVoltages object containing the computed feedforward voltages.
*/
public DifferentialDriveWheelVoltages calculate(
@@ -79,8 +79,8 @@ public DifferentialDriveWheelVoltages calculate(
double nextLeftVelocity,
double currentRightVelocity,
double nextRightVelocity,
- double dtSeconds) {
- var feedforward = new LinearPlantInversionFeedforward<>(m_plant, dtSeconds);
+ double dt) {
+ var feedforward = new LinearPlantInversionFeedforward<>(m_plant, dt);
var r = VecBuilder.fill(currentLeftVelocity, currentRightVelocity);
var nextR = VecBuilder.fill(nextLeftVelocity, nextRightVelocity);
var u = feedforward.calculate(r, nextR);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
index 44212700881..2f06a610788 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
@@ -41,12 +41,12 @@ public class ElevatorFeedforward implements ProtobufSerializable, StructSerializ
* @param kg The gravity gain in volts.
* @param kv The velocity gain in V/(m/s).
* @param ka The acceleration gain in V/(m/s²).
- * @param dtSeconds The period in seconds.
+ * @param dt The period in seconds.
* @throws IllegalArgumentException for kv < zero.
* @throws IllegalArgumentException for ka < zero.
* @throws IllegalArgumentException for period ≤ zero.
*/
- public ElevatorFeedforward(double ks, double kg, double kv, double ka, double dtSeconds) {
+ public ElevatorFeedforward(double ks, double kg, double kv, double ka, double dt) {
this.ks = ks;
this.kg = kg;
this.kv = kv;
@@ -57,11 +57,10 @@ public ElevatorFeedforward(double ks, double kg, double kv, double ka, double dt
if (ka < 0.0) {
throw new IllegalArgumentException("ka must be a non-negative number, got " + ka + "!");
}
- if (dtSeconds <= 0.0) {
- throw new IllegalArgumentException(
- "period must be a positive number, got " + dtSeconds + "!");
+ if (dt <= 0.0) {
+ throw new IllegalArgumentException("period must be a positive number, got " + dt + "!");
}
- m_dt = dtSeconds;
+ m_dt = dt;
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
index c1c30d42d21..f030a3b5cb0 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
@@ -77,14 +77,14 @@ public void setTolerance(Pose2d tolerance) {
*
* @param currentPose The current pose, as measured by odometry or pose estimator.
* @param trajectoryPose The desired trajectory pose, as sampled for the current timestep.
- * @param desiredLinearVelocityMetersPerSecond The desired linear velocity.
+ * @param desiredLinearVelocity The desired linear velocity in m/s.
* @param desiredHeading The desired heading.
* @return The next output of the holonomic drive controller.
*/
public ChassisSpeeds calculate(
Pose2d currentPose,
Pose2d trajectoryPose,
- double desiredLinearVelocityMetersPerSecond,
+ double desiredLinearVelocity,
Rotation2d desiredHeading) {
// If this is the first run, then we need to reset the theta controller to the current pose's
// heading.
@@ -94,8 +94,8 @@ public ChassisSpeeds calculate(
}
// Calculate feedforward velocities (field-relative).
- double xFF = desiredLinearVelocityMetersPerSecond * trajectoryPose.getRotation().getCos();
- double yFF = desiredLinearVelocityMetersPerSecond * trajectoryPose.getRotation().getSin();
+ double xFF = desiredLinearVelocity * trajectoryPose.getRotation().getCos();
+ double yFF = desiredLinearVelocity * trajectoryPose.getRotation().getSin();
double thetaFF =
m_thetaController.calculate(
currentPose.getRotation().getRadians(), desiredHeading.getRadians());
@@ -113,8 +113,8 @@ public ChassisSpeeds calculate(
double yFeedback = m_yController.calculate(currentPose.getY(), trajectoryPose.getY());
// Return next output.
- speeds.vxMetersPerSecond += xFeedback;
- speeds.vyMetersPerSecond += yFeedback;
+ speeds.vx += xFeedback;
+ speeds.vy += yFeedback;
speeds.toRobotRelativeSpeeds(currentPose.getRotation());
return speeds;
}
@@ -129,8 +129,7 @@ public ChassisSpeeds calculate(
*/
public ChassisSpeeds calculate(
Pose2d currentPose, Trajectory.State desiredState, Rotation2d desiredHeading) {
- return calculate(
- currentPose, desiredState.poseMeters, desiredState.velocityMetersPerSecond, desiredHeading);
+ return calculate(currentPose, desiredState.pose, desiredState.velocity, desiredHeading);
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
index 1f6ca64bb96..6e212780d2c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
@@ -242,10 +242,8 @@ public DifferentialDriveWheelVoltages calculate(
currentPose,
leftVelocity,
rightVelocity,
- desiredState.poseMeters,
- desiredState.velocityMetersPerSecond
- * (1 - (desiredState.curvatureRadPerMeter * m_trackwidth / 2.0)),
- desiredState.velocityMetersPerSecond
- * (1 + (desiredState.curvatureRadPerMeter * m_trackwidth / 2.0)));
+ desiredState.pose,
+ desiredState.velocity * (1 - (desiredState.curvature * m_trackwidth / 2.0)),
+ desiredState.velocity * (1 + (desiredState.curvature * m_trackwidth / 2.0)));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
index 5cbfc037555..e763553126d 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
@@ -201,9 +201,9 @@ public ChassisSpeeds calculate(
public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
return calculate(
currentPose,
- desiredState.poseMeters,
- desiredState.velocityMetersPerSecond,
- desiredState.velocityMetersPerSecond * desiredState.curvatureRadPerMeter);
+ desiredState.pose,
+ desiredState.velocity,
+ desiredState.velocity * desiredState.curvature);
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
index f71465a82a2..cba235d5717 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
@@ -40,11 +40,10 @@ public class LinearPlantInversionFeedforward<
* Constructs a feedforward with the given plant.
*
* @param plant The plant being controlled.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
*/
- public LinearPlantInversionFeedforward(
- LinearSystem plant, double dtSeconds) {
- this(plant.getA(), plant.getB(), dtSeconds);
+ public LinearPlantInversionFeedforward(LinearSystem plant, double dt) {
+ this(plant.getA(), plant.getB(), dt);
}
/**
@@ -52,11 +51,11 @@ public LinearPlantInversionFeedforward(
*
* @param A Continuous system matrix of the plant being controlled.
* @param B Continuous input matrix of the plant being controlled.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
*/
public LinearPlantInversionFeedforward(
- Matrix A, Matrix B, double dtSeconds) {
- var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
+ Matrix A, Matrix B, double dt) {
+ var discABPair = Discretization.discretizeAB(A, B, dt);
this.m_A = discABPair.getFirst();
this.m_B = discABPair.getSecond();
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
index 7b06a503401..8f8845f48d2 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java
@@ -45,20 +45,20 @@ public class LinearQuadraticRegulator plant,
Vector qelms,
Vector relms,
- double dtSeconds) {
+ double dt) {
this(
plant.getA(),
plant.getB(),
StateSpaceUtil.makeCostMatrix(qelms),
StateSpaceUtil.makeCostMatrix(relms),
- dtSeconds);
+ dt);
}
/**
@@ -72,7 +72,7 @@ public LinearQuadraticRegulator(
* @param B Continuous input matrix of the plant being controlled.
* @param qelms The maximum desired error tolerance for each state.
* @param relms The maximum desired control effort for each input.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @throws IllegalArgumentException If the system is unstabilizable.
*/
public LinearQuadraticRegulator(
@@ -80,13 +80,8 @@ public LinearQuadraticRegulator(
Matrix B,
Vector qelms,
Vector relms,
- double dtSeconds) {
- this(
- A,
- B,
- StateSpaceUtil.makeCostMatrix(qelms),
- StateSpaceUtil.makeCostMatrix(relms),
- dtSeconds);
+ double dt) {
+ this(A, B, StateSpaceUtil.makeCostMatrix(qelms), StateSpaceUtil.makeCostMatrix(relms), dt);
}
/**
@@ -96,7 +91,7 @@ public LinearQuadraticRegulator(
* @param B Continuous input matrix of the plant being controlled.
* @param Q The state cost matrix.
* @param R The input cost matrix.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @throws IllegalArgumentException If the system is unstabilizable.
*/
public LinearQuadraticRegulator(
@@ -104,8 +99,8 @@ public LinearQuadraticRegulator(
Matrix B,
Matrix Q,
Matrix R,
- double dtSeconds) {
- var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
+ double dt) {
+ var discABPair = Discretization.discretizeAB(A, B, dt);
var discA = discABPair.getFirst();
var discB = discABPair.getSecond();
@@ -134,7 +129,7 @@ public LinearQuadraticRegulator(
* @param Q The state cost matrix.
* @param R The input cost matrix.
* @param N The state-input cross-term cost matrix.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @throws IllegalArgumentException If the system is unstabilizable.
*/
public LinearQuadraticRegulator(
@@ -143,8 +138,8 @@ public LinearQuadraticRegulator(
Matrix Q,
Matrix R,
Matrix N,
- double dtSeconds) {
- var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
+ double dt) {
+ var discABPair = Discretization.discretizeAB(A, B, dt);
var discA = discABPair.getFirst();
var discB = discABPair.getSecond();
@@ -253,15 +248,15 @@ public Matrix calculate(Matrix x, Matrix nex
* appendix C.4 for a derivation.
*
* @param plant The plant being controlled.
- * @param dtSeconds Discretization timestep in seconds.
+ * @param dt Discretization timestep in seconds.
* @param inputDelaySeconds Input time delay in seconds.
*/
public void latencyCompensate(
- LinearSystem plant, double dtSeconds, double inputDelaySeconds) {
- var discABPair = Discretization.discretizeAB(plant.getA(), plant.getB(), dtSeconds);
+ LinearSystem plant, double dt, double inputDelaySeconds) {
+ var discABPair = Discretization.discretizeAB(plant.getA(), plant.getB(), dt);
var discA = discABPair.getFirst();
var discB = discABPair.getSecond();
- m_K = m_K.times((discA.minus(discB.times(m_K))).pow(inputDelaySeconds / dtSeconds));
+ m_K = m_K.times((discA.minus(discB.times(m_K))).pow(inputDelaySeconds / dt));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
index e9e6a3f22d9..d4b211602b2 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
@@ -31,12 +31,12 @@ public class SimpleMotorFeedforward implements ProtobufSerializable, StructSeria
* @param ks The static gain in volts.
* @param kv The velocity gain in V/(units/s).
* @param ka The acceleration gain in V/(units/s²).
- * @param dtSeconds The period in seconds.
+ * @param dt The period in seconds.
* @throws IllegalArgumentException for kv < zero.
* @throws IllegalArgumentException for ka < zero.
* @throws IllegalArgumentException for period ≤ zero.
*/
- public SimpleMotorFeedforward(double ks, double kv, double ka, double dtSeconds) {
+ public SimpleMotorFeedforward(double ks, double kv, double ka, double dt) {
this.ks = ks;
this.kv = kv;
this.ka = ka;
@@ -46,11 +46,10 @@ public SimpleMotorFeedforward(double ks, double kv, double ka, double dtSeconds)
if (ka < 0.0) {
throw new IllegalArgumentException("ka must be a non-negative number, got " + ka + "!");
}
- if (dtSeconds <= 0.0) {
- throw new IllegalArgumentException(
- "period must be a positive number, got " + dtSeconds + "!");
+ if (dt <= 0.0) {
+ throw new IllegalArgumentException("period must be a positive number, got " + dt + "!");
}
- m_dt = dtSeconds;
+ m_dt = dt;
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
index 7918f9fbb8e..0d0ccccee16 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
@@ -38,22 +38,22 @@ public class DifferentialDrivePoseEstimator extends PoseEstimator stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new DifferentialDriveOdometry(
- gyroAngle, leftDistanceMeters, rightDistanceMeters, initialPoseMeters),
+ new DifferentialDriveOdometry(gyroAngle, leftDistance, rightDistance, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
}
@@ -96,19 +95,14 @@ public DifferentialDrivePoseEstimator(
* automatically takes care of offsetting the gyro angle.
*
* @param gyroAngle The angle reported by the gyroscope.
- * @param leftPositionMeters The distance traveled by the left encoder.
- * @param rightPositionMeters The distance traveled by the right encoder.
- * @param poseMeters The position on the field that your robot is at.
+ * @param leftPosition The distance traveled by the left encoder in meters.
+ * @param rightPosition The distance traveled by the right encoder in meters.
+ * @param pose The position on the field that your robot is at.
*/
public void resetPosition(
- Rotation2d gyroAngle,
- double leftPositionMeters,
- double rightPositionMeters,
- Pose2d poseMeters) {
+ Rotation2d gyroAngle, double leftPosition, double rightPosition, Pose2d pose) {
resetPosition(
- gyroAngle,
- new DifferentialDriveWheelPositions(leftPositionMeters, rightPositionMeters),
- poseMeters);
+ gyroAngle, new DifferentialDriveWheelPositions(leftPosition, rightPosition), pose);
}
/**
@@ -116,34 +110,27 @@ public void resetPosition(
* loop.
*
* @param gyroAngle The current gyro angle.
- * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
- * @param distanceRightMeters The total distance travelled by the right wheel in meters.
+ * @param distanceLeft The total distance travelled by the left wheel in meters.
+ * @param distanceRight The total distance travelled by the right wheel in meters.
* @return The estimated pose of the robot in meters.
*/
- public Pose2d update(
- Rotation2d gyroAngle, double distanceLeftMeters, double distanceRightMeters) {
- return update(
- gyroAngle, new DifferentialDriveWheelPositions(distanceLeftMeters, distanceRightMeters));
+ public Pose2d update(Rotation2d gyroAngle, double distanceLeft, double distanceRight) {
+ return update(gyroAngle, new DifferentialDriveWheelPositions(distanceLeft, distanceRight));
}
/**
* Updates the pose estimator with wheel encoder and gyro information. This should be called every
* loop.
*
- * @param currentTimeSeconds Time at which this method was called, in seconds.
+ * @param currentTime Time at which this method was called, in seconds.
* @param gyroAngle The current gyro angle.
- * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
- * @param distanceRightMeters The total distance travelled by the right wheel in meters.
+ * @param distanceLeft The total distance travelled by the left wheel in meters.
+ * @param distanceRight The total distance travelled by the right wheel in meters.
* @return The estimated pose of the robot in meters.
*/
public Pose2d updateWithTime(
- double currentTimeSeconds,
- Rotation2d gyroAngle,
- double distanceLeftMeters,
- double distanceRightMeters) {
+ double currentTime, Rotation2d gyroAngle, double distanceLeft, double distanceRight) {
return updateWithTime(
- currentTimeSeconds,
- gyroAngle,
- new DifferentialDriveWheelPositions(distanceLeftMeters, distanceRightMeters));
+ currentTime, gyroAngle, new DifferentialDriveWheelPositions(distanceLeft, distanceRight));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator3d.java
index 470a05aa373..0c437296cbf 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator3d.java
@@ -48,22 +48,22 @@ public class DifferentialDrivePoseEstimator3d
*
* @param kinematics A correctly-configured kinematics object for your drivetrain.
* @param gyroAngle The current gyro angle.
- * @param leftDistanceMeters The distance traveled by the left encoder.
- * @param rightDistanceMeters The distance traveled by the right encoder.
- * @param initialPoseMeters The starting pose estimate.
+ * @param leftDistance The distance traveled by the left encoder in meters.
+ * @param rightDistance The distance traveled by the right encoder in meters.
+ * @param initialPose The starting pose estimate.
*/
public DifferentialDrivePoseEstimator3d(
DifferentialDriveKinematics kinematics,
Rotation3d gyroAngle,
- double leftDistanceMeters,
- double rightDistanceMeters,
- Pose3d initialPoseMeters) {
+ double leftDistance,
+ double rightDistance,
+ Pose3d initialPose) {
this(
kinematics,
gyroAngle,
- leftDistanceMeters,
- rightDistanceMeters,
- initialPoseMeters,
+ leftDistance,
+ rightDistance,
+ initialPose,
VecBuilder.fill(0.02, 0.02, 0.02, 0.01),
VecBuilder.fill(0.1, 0.1, 0.1, 0.1));
}
@@ -73,9 +73,9 @@ public DifferentialDrivePoseEstimator3d(
*
* @param kinematics A correctly-configured kinematics object for your drivetrain.
* @param gyroAngle The gyro angle of the robot.
- * @param leftDistanceMeters The distance traveled by the left encoder.
- * @param rightDistanceMeters The distance traveled by the right encoder.
- * @param initialPoseMeters The estimated initial pose.
+ * @param leftDistance The distance traveled by the left encoder in meters.
+ * @param rightDistance The distance traveled by the right encoder in meters.
+ * @param initialPose The estimated initial pose.
* @param stateStdDevs Standard deviations of the pose estimate (x position in meters, y position
* in meters, and heading in radians). Increase these numbers to trust your state estimate
* less.
@@ -86,15 +86,14 @@ public DifferentialDrivePoseEstimator3d(
public DifferentialDrivePoseEstimator3d(
DifferentialDriveKinematics kinematics,
Rotation3d gyroAngle,
- double leftDistanceMeters,
- double rightDistanceMeters,
- Pose3d initialPoseMeters,
+ double leftDistance,
+ double rightDistance,
+ Pose3d initialPose,
Matrix stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new DifferentialDriveOdometry3d(
- gyroAngle, leftDistanceMeters, rightDistanceMeters, initialPoseMeters),
+ new DifferentialDriveOdometry3d(gyroAngle, leftDistance, rightDistance, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
}
@@ -106,19 +105,14 @@ public DifferentialDrivePoseEstimator3d(
* automatically takes care of offsetting the gyro angle.
*
* @param gyroAngle The angle reported by the gyroscope.
- * @param leftPositionMeters The distance traveled by the left encoder.
- * @param rightPositionMeters The distance traveled by the right encoder.
- * @param poseMeters The position on the field that your robot is at.
+ * @param leftPosition The distance traveled by the left encoder in meters.
+ * @param rightPosition The distance traveled by the right encoder in meters.
+ * @param pose The position on the field that your robot is at.
*/
public void resetPosition(
- Rotation3d gyroAngle,
- double leftPositionMeters,
- double rightPositionMeters,
- Pose3d poseMeters) {
+ Rotation3d gyroAngle, double leftPosition, double rightPosition, Pose3d pose) {
resetPosition(
- gyroAngle,
- new DifferentialDriveWheelPositions(leftPositionMeters, rightPositionMeters),
- poseMeters);
+ gyroAngle, new DifferentialDriveWheelPositions(leftPosition, rightPosition), pose);
}
/**
@@ -126,34 +120,27 @@ public void resetPosition(
* loop.
*
* @param gyroAngle The current gyro angle.
- * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
- * @param distanceRightMeters The total distance travelled by the right wheel in meters.
+ * @param distanceLeft The total distance travelled by the left wheel in meters.
+ * @param distanceRight The total distance travelled by the right wheel in meters.
* @return The estimated pose of the robot in meters.
*/
- public Pose3d update(
- Rotation3d gyroAngle, double distanceLeftMeters, double distanceRightMeters) {
- return update(
- gyroAngle, new DifferentialDriveWheelPositions(distanceLeftMeters, distanceRightMeters));
+ public Pose3d update(Rotation3d gyroAngle, double distanceLeft, double distanceRight) {
+ return update(gyroAngle, new DifferentialDriveWheelPositions(distanceLeft, distanceRight));
}
/**
* Updates the pose estimator with wheel encoder and gyro information. This should be called every
* loop.
*
- * @param currentTimeSeconds Time at which this method was called, in seconds.
+ * @param currentTime Time at which this method was called, in seconds.
* @param gyroAngle The current gyro angle.
- * @param distanceLeftMeters The total distance travelled by the left wheel in meters.
- * @param distanceRightMeters The total distance travelled by the right wheel in meters.
+ * @param distanceLeft The total distance travelled by the left wheel in meters.
+ * @param distanceRight The total distance travelled by the right wheel in meters.
* @return The estimated pose of the robot in meters.
*/
public Pose3d updateWithTime(
- double currentTimeSeconds,
- Rotation3d gyroAngle,
- double distanceLeftMeters,
- double distanceRightMeters) {
+ double currentTime, Rotation3d gyroAngle, double distanceLeft, double distanceRight) {
return updateWithTime(
- currentTimeSeconds,
- gyroAngle,
- new DifferentialDriveWheelPositions(distanceLeftMeters, distanceRightMeters));
+ currentTime, gyroAngle, new DifferentialDriveWheelPositions(distanceLeft, distanceRight));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
index 055bf9939af..78bc3d13358 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
@@ -58,7 +58,7 @@ public class ExtendedKalmanFilter m_P;
- private double m_dtSeconds;
+ private double m_dt;
/**
* Constructs an extended Kalman filter.
@@ -74,7 +74,7 @@ public class ExtendedKalmanFilter states,
@@ -84,7 +84,7 @@ public ExtendedKalmanFilter(
BiFunction, Matrix, Matrix> h,
Matrix stateStdDevs,
Matrix measurementStdDevs,
- double dtSeconds) {
+ double dt) {
this(
states,
inputs,
@@ -95,7 +95,7 @@ public ExtendedKalmanFilter(
measurementStdDevs,
Matrix::minus,
Matrix::plus,
- dtSeconds);
+ dt);
}
/**
@@ -115,7 +115,7 @@ public ExtendedKalmanFilter(
* @param residualFuncY A function that computes the residual of two measurement vectors (i.e. it
* subtracts them.)
* @param addFuncX A function that adds two state vectors.
- * @param dtSeconds Nominal discretization timestep.
+ * @param dt Nominal discretization timestep in seconds.
*/
public ExtendedKalmanFilter(
Nat states,
@@ -127,7 +127,7 @@ public ExtendedKalmanFilter(
Matrix measurementStdDevs,
BiFunction, Matrix, Matrix> residualFuncY,
BiFunction, Matrix, Matrix> addFuncX,
- double dtSeconds) {
+ double dt) {
m_states = states;
m_outputs = outputs;
@@ -139,7 +139,7 @@ public ExtendedKalmanFilter(
m_contQ = StateSpaceUtil.makeCovarianceMatrix(states, stateStdDevs);
m_contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
- m_dtSeconds = dtSeconds;
+ m_dt = dt;
reset();
@@ -150,11 +150,11 @@ public ExtendedKalmanFilter(
NumericalJacobian.numericalJacobianX(
outputs, states, h, m_xHat, new Matrix<>(inputs, Nat.N1()));
- final var discPair = Discretization.discretizeAQ(contA, m_contQ, dtSeconds);
+ final var discPair = Discretization.discretizeAQ(contA, m_contQ, dt);
final var discA = discPair.getFirst();
final var discQ = discPair.getSecond();
- final var discR = Discretization.discretizeR(m_contR, dtSeconds);
+ final var discR = Discretization.discretizeR(m_contR, dt);
if (StateSpaceUtil.isDetectable(discA, C) && outputs.getNum() <= states.getNum()) {
m_initP = DARE.dare(discA.transpose(), C.transpose(), discQ, discR);
@@ -249,11 +249,11 @@ public final void reset() {
* Project the model into the future with a new control input u.
*
* @param u New control input from controller.
- * @param dtSeconds Timestep for prediction.
+ * @param dt Timestep for prediction in seconds.
*/
@Override
- public void predict(Matrix u, double dtSeconds) {
- predict(u, m_f, dtSeconds);
+ public void predict(Matrix u, double dt) {
+ predict(u, m_f, dt);
}
/**
@@ -261,26 +261,26 @@ public void predict(Matrix u, double dtSeconds) {
*
* @param u New control input from controller.
* @param f The function used to linearize the model.
- * @param dtSeconds Timestep for prediction.
+ * @param dt Timestep for prediction in seconds.
*/
public void predict(
Matrix u,
BiFunction, Matrix, Matrix> f,
- double dtSeconds) {
+ double dt) {
// Find continuous A
final var contA = NumericalJacobian.numericalJacobianX(m_states, m_states, f, m_xHat, u);
// Find discrete A and Q
- final var discPair = Discretization.discretizeAQ(contA, m_contQ, dtSeconds);
+ final var discPair = Discretization.discretizeAQ(contA, m_contQ, dt);
final var discA = discPair.getFirst();
final var discQ = discPair.getSecond();
- m_xHat = NumericalIntegration.rk4(f, m_xHat, u, dtSeconds);
+ m_xHat = NumericalIntegration.rk4(f, m_xHat, u, dt);
// Pₖ₊₁⁻ = APₖ⁻Aᵀ + Q
m_P = discA.times(m_P).times(discA.transpose()).plus(discQ);
- m_dtSeconds = dtSeconds;
+ m_dt = dt;
}
/**
@@ -356,7 +356,7 @@ public void correct(
BiFunction, Matrix, Matrix> residualFuncY,
BiFunction, Matrix, Matrix> addFuncX) {
final var C = NumericalJacobian.numericalJacobianX(rows, m_states, h, m_xHat, u);
- final var discR = Discretization.discretizeR(R, m_dtSeconds);
+ final var discR = Discretization.discretizeR(R, m_dt);
final var S = C.times(m_P).times(C.transpose()).plus(discR);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
index 40e6c96c7a7..8302cd554b2 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java
@@ -41,7 +41,7 @@ public class KalmanFilter m_P;
private final Matrix m_contQ;
private final Matrix m_contR;
- private double m_dtSeconds;
+ private double m_dt;
private final Matrix m_initP;
@@ -57,7 +57,7 @@ public class KalmanFilter plant,
Matrix stateStdDevs,
Matrix measurementStdDevs,
- double dtSeconds) {
+ double dt) {
this.m_states = states;
this.m_plant = plant;
m_contQ = StateSpaceUtil.makeCovarianceMatrix(states, stateStdDevs);
m_contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
- m_dtSeconds = dtSeconds;
+ m_dt = dt;
// Find discrete A and Q
- var pair = Discretization.discretizeAQ(plant.getA(), m_contQ, dtSeconds);
+ var pair = Discretization.discretizeAQ(plant.getA(), m_contQ, dt);
var discA = pair.getFirst();
var discQ = pair.getSecond();
- var discR = Discretization.discretizeR(m_contR, dtSeconds);
+ var discR = Discretization.discretizeR(m_contR, dt);
var C = plant.getC();
@@ -173,21 +173,21 @@ public final void reset() {
* Project the model into the future with a new control input u.
*
* @param u New control input from controller.
- * @param dtSeconds Timestep for prediction.
+ * @param dt Timestep for prediction in seconds.
*/
@Override
- public void predict(Matrix u, double dtSeconds) {
+ public void predict(Matrix u, double dt) {
// Find discrete A and Q
- final var discPair = Discretization.discretizeAQ(m_plant.getA(), m_contQ, dtSeconds);
+ final var discPair = Discretization.discretizeAQ(m_plant.getA(), m_contQ, dt);
final var discA = discPair.getFirst();
final var discQ = discPair.getSecond();
- m_xHat = m_plant.calculateX(m_xHat, u, dtSeconds);
+ m_xHat = m_plant.calculateX(m_xHat, u, dt);
// Pₖ₊₁⁻ = APₖ⁻Aᵀ + Q
m_P = discA.times(m_P).times(discA.transpose()).plus(discQ);
- m_dtSeconds = dtSeconds;
+ m_dt = dt;
}
/**
@@ -214,7 +214,7 @@ public void correct(Matrix u, Matrix y, Matrix observer,
- Matrix u,
- Matrix localY,
- double timestampSeconds) {
- m_pastObserverSnapshots.add(
- Map.entry(timestampSeconds, new ObserverSnapshot(observer, u, localY)));
+ KalmanTypeFilter observer, Matrix u, Matrix localY, double timestamp) {
+ m_pastObserverSnapshots.add(Map.entry(timestamp, new ObserverSnapshot(observer, u, localY)));
if (m_pastObserverSnapshots.size() > kMaxPastObserverStates) {
m_pastObserverSnapshots.remove(0);
@@ -65,7 +61,7 @@ public void addObserverState(
* @param nominalDtSeconds The nominal timestep.
* @param y The measurement.
* @param globalMeasurementCorrect The function take calls correct() on the observer.
- * @param timestampSeconds The timestamp of the measurement.
+ * @param timestamp The timestamp of the measurement in seconds.
*/
public void applyPastGlobalMeasurement(
Nat rows,
@@ -73,16 +69,13 @@ public void applyPastGlobalMeasurement(
double nominalDtSeconds,
Matrix y,
BiConsumer, Matrix> globalMeasurementCorrect,
- double timestampSeconds) {
+ double timestamp) {
if (m_pastObserverSnapshots.isEmpty()) {
// State map was empty, which means that we got a past measurement right at startup. The only
// thing we can really do is ignore the measurement.
return;
}
- // Use a less verbose name for timestamp
- double timestamp = timestampSeconds;
-
int maxIdx = m_pastObserverSnapshots.size() - 1;
int low = 0;
int high = maxIdx;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
index ff9856c32df..a072be98e14 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
@@ -76,9 +76,9 @@ public interface KalmanTypeFilter u, double dtSeconds);
+ void predict(Matrix u, double dt);
/**
* Correct the state estimate x-hat using the measurements in y.
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
index e33b30d09ca..cec0960f11b 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
@@ -37,18 +37,18 @@ public class MecanumDrivePoseEstimator extends PoseEstimator stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new MecanumDriveOdometry(kinematics, gyroAngle, wheelPositions, initialPoseMeters),
+ new MecanumDriveOdometry(kinematics, gyroAngle, wheelPositions, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator3d.java
index e2f7acfdb0c..306d06aa7db 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator3d.java
@@ -46,18 +46,18 @@ public class MecanumDrivePoseEstimator3d extends PoseEstimator3d stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new MecanumDriveOdometry3d(kinematics, gyroAngle, wheelPositions, initialPoseMeters),
+ new MecanumDriveOdometry3d(kinematics, gyroAngle, wheelPositions, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java
index 1f00cb7b187..2cfe982ce34 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java
@@ -73,7 +73,7 @@ public PoseEstimator(
Matrix visionMeasurementStdDevs) {
m_odometry = odometry;
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
for (int i = 0; i < 3; ++i) {
m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0));
@@ -116,14 +116,14 @@ public final void setVisionMeasurementStdDevs(Matrix visionMeasurementSt
*
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param poseMeters The position on the field that your robot is at.
+ * @param pose The position on the field that your robot is at.
*/
- public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters) {
+ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d pose) {
// Reset state estimate and error covariance
- m_odometry.resetPosition(gyroAngle, wheelPositions, poseMeters);
+ m_odometry.resetPosition(gyroAngle, wheelPositions, pose);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -135,7 +135,7 @@ public void resetPose(Pose2d pose) {
m_odometry.resetPose(pose);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -147,7 +147,7 @@ public void resetTranslation(Translation2d translation) {
m_odometry.resetTranslation(translation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -159,7 +159,7 @@ public void resetRotation(Rotation2d rotation) {
m_odometry.resetRotation(rotation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -174,10 +174,10 @@ public Pose2d getEstimatedPosition() {
/**
* Return the pose at a given timestamp, if the buffer is not empty.
*
- * @param timestampSeconds The pose's timestamp in seconds.
+ * @param timestamp The pose's timestamp in seconds.
* @return The pose at the given timestamp (or Optional.empty() if the buffer is empty).
*/
- public Optional sampleAt(double timestampSeconds) {
+ public Optional sampleAt(double timestamp) {
// Step 0: If there are no odometry updates to sample, skip.
if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()) {
return Optional.empty();
@@ -187,20 +187,19 @@ public Optional sampleAt(double timestampSeconds) {
// the buffer will always use a timestamp between the first and last timestamps)
double oldestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().firstKey();
double newestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().lastKey();
- timestampSeconds =
- MathUtil.clamp(timestampSeconds, oldestOdometryTimestamp, newestOdometryTimestamp);
+ timestamp = MathUtil.clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
// Step 2: If there are no applicable vision updates, use the odometry-only information.
- if (m_visionUpdates.isEmpty() || timestampSeconds < m_visionUpdates.firstKey()) {
- return m_odometryPoseBuffer.getSample(timestampSeconds);
+ if (m_visionUpdates.isEmpty() || timestamp < m_visionUpdates.firstKey()) {
+ return m_odometryPoseBuffer.getSample(timestamp);
}
// Step 3: Get the latest vision update from before or at the timestamp to sample at.
- double floorTimestamp = m_visionUpdates.floorKey(timestampSeconds);
+ double floorTimestamp = m_visionUpdates.floorKey(timestamp);
var visionUpdate = m_visionUpdates.get(floorTimestamp);
// Step 4: Get the pose measured by odometry at the time of the sample.
- var odometryEstimate = m_odometryPoseBuffer.getSample(timestampSeconds);
+ var odometryEstimate = m_odometryPoseBuffer.getSample(timestamp);
// Step 5: Apply the vision compensation to the odometry pose.
return odometryEstimate.map(odometryPose -> visionUpdate.compensate(odometryPose));
@@ -239,19 +238,18 @@ private void cleanUpVisionUpdates() {
* recommend only adding vision measurements that are already within one meter or so of the
* current pose estimate.
*
- * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
- * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
- * don't use your own time source by calling {@link
+ * @param visionRobotPose The pose of the robot as measured by the vision camera.
+ * @param timestamp The timestamp of the vision measurement in seconds. Note that if you don't use
+ * your own time source by calling {@link
* PoseEstimator#updateWithTime(double,Rotation2d,Object)} then you must use a timestamp with
* an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as {@link
* edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.) This means that you should use {@link
* edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source or sync the epochs.
*/
- public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
+ public void addVisionMeasurement(Pose2d visionRobotPose, double timestamp) {
// Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip.
if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()
- || m_odometryPoseBuffer.getInternalBuffer().lastKey() - kBufferDuration
- > timestampSeconds) {
+ || m_odometryPoseBuffer.getInternalBuffer().lastKey() - kBufferDuration > timestamp) {
return;
}
@@ -259,7 +257,7 @@ public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampS
cleanUpVisionUpdates();
// Step 2: Get the pose measured by odometry at the moment the vision measurement was made.
- var odometrySample = m_odometryPoseBuffer.getSample(timestampSeconds);
+ var odometrySample = m_odometryPoseBuffer.getSample(timestamp);
if (odometrySample.isEmpty()) {
return;
@@ -267,14 +265,14 @@ public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampS
// Step 3: Get the vision-compensated pose estimate at the moment the vision measurement was
// made.
- var visionSample = sampleAt(timestampSeconds);
+ var visionSample = sampleAt(timestamp);
if (visionSample.isEmpty()) {
return;
}
// Step 4: Measure the twist between the old pose estimate and the vision pose.
- var twist = visionSample.get().log(visionRobotPoseMeters);
+ var twist = visionSample.get().log(visionRobotPose);
// Step 5: We should not trust the twist entirely, so instead we scale this twist by a Kalman
// gain matrix representing how much we trust vision measurements compared to our current pose.
@@ -286,14 +284,14 @@ public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampS
// Step 7: Calculate and record the vision update.
var visionUpdate = new VisionUpdate(visionSample.get().exp(scaledTwist), odometrySample.get());
- m_visionUpdates.put(timestampSeconds, visionUpdate);
+ m_visionUpdates.put(timestamp, visionUpdate);
// Step 8: Remove later vision measurements. (Matches previous behavior)
- m_visionUpdates.tailMap(timestampSeconds, false).entrySet().clear();
+ m_visionUpdates.tailMap(timestamp, false).entrySet().clear();
// Step 9: Update latest pose estimate. Since we cleared all updates after this vision update,
// it's guaranteed to be the latest vision update.
- m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters());
+ m_poseEstimate = visionUpdate.compensate(m_odometry.getPose());
}
/**
@@ -311,23 +309,20 @@ public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampS
* to apply to future measurements until a subsequent call to {@link
* PoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method.
*
- * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
- * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
- * don't use your own time source by calling {@link #updateWithTime}, then you must use a
- * timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same
- * epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that you
- * should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source in
- * this case.
+ * @param visionRobotPose The pose of the robot as measured by the vision camera.
+ * @param timestamp The timestamp of the vision measurement in seconds. Note that if you don't use
+ * your own time source by calling {@link #updateWithTime}, then you must use a timestamp with
+ * an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as {@link
+ * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that you should use {@link
+ * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source in this case.
* @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
* in meters, y position in meters, and heading in radians). Increase these numbers to trust
* the vision pose measurement less.
*/
public void addVisionMeasurement(
- Pose2d visionRobotPoseMeters,
- double timestampSeconds,
- Matrix visionMeasurementStdDevs) {
+ Pose2d visionRobotPose, double timestamp, Matrix visionMeasurementStdDevs) {
setVisionMeasurementStdDevs(visionMeasurementStdDevs);
- addVisionMeasurement(visionRobotPoseMeters, timestampSeconds);
+ addVisionMeasurement(visionRobotPose, timestamp);
}
/**
@@ -346,15 +341,15 @@ public Pose2d update(Rotation2d gyroAngle, T wheelPositions) {
* Updates the pose estimator with wheel encoder and gyro information. This should be called every
* loop.
*
- * @param currentTimeSeconds Time at which this method was called, in seconds.
+ * @param currentTime Time at which this method was called, in seconds.
* @param gyroAngle The current gyro angle.
* @param wheelPositions The current encoder readings.
* @return The estimated pose of the robot in meters.
*/
- public Pose2d updateWithTime(double currentTimeSeconds, Rotation2d gyroAngle, T wheelPositions) {
+ public Pose2d updateWithTime(double currentTime, Rotation2d gyroAngle, T wheelPositions) {
var odometryEstimate = m_odometry.update(gyroAngle, wheelPositions);
- m_odometryPoseBuffer.addSample(currentTimeSeconds, odometryEstimate);
+ m_odometryPoseBuffer.addSample(currentTime, odometryEstimate);
if (m_visionUpdates.isEmpty()) {
m_poseEstimate = odometryEstimate;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java
index 9ce96f0243b..31c97549ff5 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java
@@ -81,7 +81,7 @@ public PoseEstimator3d(
Matrix visionMeasurementStdDevs) {
m_odometry = odometry;
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
for (int i = 0; i < 4; ++i) {
m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0));
@@ -128,14 +128,14 @@ public final void setVisionMeasurementStdDevs(Matrix visionMeasurementSt
*
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param poseMeters The position on the field that your robot is at.
+ * @param pose The position on the field that your robot is at.
*/
- public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d poseMeters) {
+ public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d pose) {
// Reset state estimate and error covariance
- m_odometry.resetPosition(gyroAngle, wheelPositions, poseMeters);
+ m_odometry.resetPosition(gyroAngle, wheelPositions, pose);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -147,7 +147,7 @@ public void resetPose(Pose3d pose) {
m_odometry.resetPose(pose);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -159,7 +159,7 @@ public void resetTranslation(Translation3d translation) {
m_odometry.resetTranslation(translation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -171,7 +171,7 @@ public void resetRotation(Rotation3d rotation) {
m_odometry.resetRotation(rotation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
- m_poseEstimate = m_odometry.getPoseMeters();
+ m_poseEstimate = m_odometry.getPose();
}
/**
@@ -186,10 +186,10 @@ public Pose3d getEstimatedPosition() {
/**
* Return the pose at a given timestamp, if the buffer is not empty.
*
- * @param timestampSeconds The pose's timestamp in seconds.
+ * @param timestamp The pose's timestamp in seconds.
* @return The pose at the given timestamp (or Optional.empty() if the buffer is empty).
*/
- public Optional sampleAt(double timestampSeconds) {
+ public Optional sampleAt(double timestamp) {
// Step 0: If there are no odometry updates to sample, skip.
if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()) {
return Optional.empty();
@@ -199,20 +199,19 @@ public Optional sampleAt(double timestampSeconds) {
// the buffer will always use a timestamp between the first and last timestamps)
double oldestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().firstKey();
double newestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().lastKey();
- timestampSeconds =
- MathUtil.clamp(timestampSeconds, oldestOdometryTimestamp, newestOdometryTimestamp);
+ timestamp = MathUtil.clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp);
// Step 2: If there are no applicable vision updates, use the odometry-only information.
- if (m_visionUpdates.isEmpty() || timestampSeconds < m_visionUpdates.firstKey()) {
- return m_odometryPoseBuffer.getSample(timestampSeconds);
+ if (m_visionUpdates.isEmpty() || timestamp < m_visionUpdates.firstKey()) {
+ return m_odometryPoseBuffer.getSample(timestamp);
}
// Step 3: Get the latest vision update from before or at the timestamp to sample at.
- double floorTimestamp = m_visionUpdates.floorKey(timestampSeconds);
+ double floorTimestamp = m_visionUpdates.floorKey(timestamp);
var visionUpdate = m_visionUpdates.get(floorTimestamp);
// Step 4: Get the pose measured by odometry at the time of the sample.
- var odometryEstimate = m_odometryPoseBuffer.getSample(timestampSeconds);
+ var odometryEstimate = m_odometryPoseBuffer.getSample(timestamp);
// Step 5: Apply the vision compensation to the odometry pose.
return odometryEstimate.map(odometryPose -> visionUpdate.compensate(odometryPose));
@@ -251,20 +250,19 @@ private void cleanUpVisionUpdates() {
* recommend only adding vision measurements that are already within one meter or so of the
* current pose estimate.
*
- * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
- * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
- * don't use your own time source by calling {@link
+ * @param visionRobotPose The pose of the robot as measured by the vision camera.
+ * @param timestamp The timestamp of the vision measurement in seconds. Note that if you don't use
+ * your own time source by calling {@link
* PoseEstimator3d#updateWithTime(double,Rotation3d,Object)} then you must use a timestamp
* with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as
* {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.) This means that you should use
* {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source or sync the
* epochs.
*/
- public void addVisionMeasurement(Pose3d visionRobotPoseMeters, double timestampSeconds) {
+ public void addVisionMeasurement(Pose3d visionRobotPose, double timestamp) {
// Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip.
if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()
- || m_odometryPoseBuffer.getInternalBuffer().lastKey() - kBufferDuration
- > timestampSeconds) {
+ || m_odometryPoseBuffer.getInternalBuffer().lastKey() - kBufferDuration > timestamp) {
return;
}
@@ -272,7 +270,7 @@ public void addVisionMeasurement(Pose3d visionRobotPoseMeters, double timestampS
cleanUpVisionUpdates();
// Step 2: Get the pose measured by odometry at the moment the vision measurement was made.
- var odometrySample = m_odometryPoseBuffer.getSample(timestampSeconds);
+ var odometrySample = m_odometryPoseBuffer.getSample(timestamp);
if (odometrySample.isEmpty()) {
return;
@@ -280,14 +278,14 @@ public void addVisionMeasurement(Pose3d visionRobotPoseMeters, double timestampS
// Step 3: Get the vision-compensated pose estimate at the moment the vision measurement was
// made.
- var visionSample = sampleAt(timestampSeconds);
+ var visionSample = sampleAt(timestamp);
if (visionSample.isEmpty()) {
return;
}
// Step 4: Measure the twist between the old pose estimate and the vision pose.
- var twist = visionSample.get().log(visionRobotPoseMeters);
+ var twist = visionSample.get().log(visionRobotPose);
// Step 5: We should not trust the twist entirely, so instead we scale this twist by a Kalman
// gain matrix representing how much we trust vision measurements compared to our current pose.
@@ -307,14 +305,14 @@ public void addVisionMeasurement(Pose3d visionRobotPoseMeters, double timestampS
// Step 7: Calculate and record the vision update.
var visionUpdate = new VisionUpdate(visionSample.get().exp(scaledTwist), odometrySample.get());
- m_visionUpdates.put(timestampSeconds, visionUpdate);
+ m_visionUpdates.put(timestamp, visionUpdate);
// Step 8: Remove later vision measurements. (Matches previous behavior)
- m_visionUpdates.tailMap(timestampSeconds, false).entrySet().clear();
+ m_visionUpdates.tailMap(timestamp, false).entrySet().clear();
// Step 9: Update latest pose estimate. Since we cleared all updates after this vision update,
// it's guaranteed to be the latest vision update.
- m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters());
+ m_poseEstimate = visionUpdate.compensate(m_odometry.getPose());
}
/**
@@ -332,23 +330,20 @@ public void addVisionMeasurement(Pose3d visionRobotPoseMeters, double timestampS
* to apply to future measurements until a subsequent call to {@link
* PoseEstimator3d#setVisionMeasurementStdDevs(Matrix)} or this method.
*
- * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera.
- * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you
- * don't use your own time source by calling {@link #updateWithTime}, then you must use a
- * timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same
- * epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that you
- * should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source in
- * this case.
+ * @param visionRobotPose The pose of the robot as measured by the vision camera.
+ * @param timestamp The timestamp of the vision measurement in seconds. Note that if you don't use
+ * your own time source by calling {@link #updateWithTime}, then you must use a timestamp with
+ * an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as {@link
+ * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that you should use {@link
+ * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source in this case.
* @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position
* in meters, y position in meters, z position in meters, and angle in radians). Increase
* these numbers to trust the vision pose measurement less.
*/
public void addVisionMeasurement(
- Pose3d visionRobotPoseMeters,
- double timestampSeconds,
- Matrix visionMeasurementStdDevs) {
+ Pose3d visionRobotPose, double timestamp, Matrix visionMeasurementStdDevs) {
setVisionMeasurementStdDevs(visionMeasurementStdDevs);
- addVisionMeasurement(visionRobotPoseMeters, timestampSeconds);
+ addVisionMeasurement(visionRobotPose, timestamp);
}
/**
@@ -367,15 +362,15 @@ public Pose3d update(Rotation3d gyroAngle, T wheelPositions) {
* Updates the pose estimator with wheel encoder and gyro information. This should be called every
* loop.
*
- * @param currentTimeSeconds Time at which this method was called, in seconds.
+ * @param currentTime Time at which this method was called, in seconds.
* @param gyroAngle The current gyro angle.
* @param wheelPositions The current encoder readings.
* @return The estimated pose of the robot in meters.
*/
- public Pose3d updateWithTime(double currentTimeSeconds, Rotation3d gyroAngle, T wheelPositions) {
+ public Pose3d updateWithTime(double currentTime, Rotation3d gyroAngle, T wheelPositions) {
var odometryEstimate = m_odometry.update(gyroAngle, wheelPositions);
- m_odometryPoseBuffer.addSample(currentTimeSeconds, odometryEstimate);
+ m_odometryPoseBuffer.addSample(currentTime, odometryEstimate);
if (m_visionUpdates.isEmpty()) {
m_poseEstimate = odometryEstimate;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java
index 31649728e27..1b85e4385e2 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java
@@ -58,7 +58,7 @@ public class SteadyStateKalmanFilter plant,
Matrix stateStdDevs,
Matrix measurementStdDevs,
- double dtSeconds) {
+ double dt) {
this.m_states = states;
this.m_plant = plant;
@@ -75,11 +75,11 @@ public SteadyStateKalmanFilter(
var contQ = StateSpaceUtil.makeCovarianceMatrix(states, stateStdDevs);
var contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
- var pair = Discretization.discretizeAQ(plant.getA(), contQ, dtSeconds);
+ var pair = Discretization.discretizeAQ(plant.getA(), contQ, dt);
var discA = pair.getFirst();
var discQ = pair.getSecond();
- var discR = Discretization.discretizeR(contR, dtSeconds);
+ var discR = Discretization.discretizeR(contR, dt);
var C = plant.getC();
@@ -174,10 +174,10 @@ public double getXhat(int row) {
* Project the model into the future with a new control input u.
*
* @param u New control input from controller.
- * @param dtSeconds Timestep for prediction.
+ * @param dt Timestep for prediction in seconds.
*/
- public void predict(Matrix u, double dtSeconds) {
- this.m_xHat = m_plant.calculateX(m_xHat, u, dtSeconds);
+ public void predict(Matrix u, double dt) {
+ this.m_xHat = m_plant.calculateX(m_xHat, u, dt);
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
index 495cd893fc6..6c51f346d2a 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
@@ -38,18 +38,18 @@ public class SwerveDrivePoseEstimator extends PoseEstimator stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new SwerveDriveOdometry(kinematics, gyroAngle, modulePositions, initialPoseMeters),
+ new SwerveDriveOdometry(kinematics, gyroAngle, modulePositions, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
@@ -86,13 +86,13 @@ public SwerveDrivePoseEstimator(
@Override
public Pose2d updateWithTime(
- double currentTimeSeconds, Rotation2d gyroAngle, SwerveModulePosition[] wheelPositions) {
+ double currentTime, Rotation2d gyroAngle, SwerveModulePosition[] wheelPositions) {
if (wheelPositions.length != m_numModules) {
throw new IllegalArgumentException(
"Number of modules is not consistent with number of wheel locations provided in "
+ "constructor");
}
- return super.updateWithTime(currentTimeSeconds, gyroAngle, wheelPositions);
+ return super.updateWithTime(currentTime, gyroAngle, wheelPositions);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3d.java
index 668f45c410e..8016a092cd8 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3d.java
@@ -47,18 +47,18 @@ public class SwerveDrivePoseEstimator3d extends PoseEstimator3d stateStdDevs,
Matrix visionMeasurementStdDevs) {
super(
kinematics,
- new SwerveDriveOdometry3d(kinematics, gyroAngle, modulePositions, initialPoseMeters),
+ new SwerveDriveOdometry3d(kinematics, gyroAngle, modulePositions, initialPose),
stateStdDevs,
visionMeasurementStdDevs);
@@ -95,13 +95,13 @@ public SwerveDrivePoseEstimator3d(
@Override
public Pose3d updateWithTime(
- double currentTimeSeconds, Rotation3d gyroAngle, SwerveModulePosition[] wheelPositions) {
+ double currentTime, Rotation3d gyroAngle, SwerveModulePosition[] wheelPositions) {
if (wheelPositions.length != m_numModules) {
throw new IllegalArgumentException(
"Number of modules is not consistent with number of wheel locations provided in "
+ "constructor");
}
- return super.updateWithTime(currentTimeSeconds, gyroAngle, wheelPositions);
+ return super.updateWithTime(currentTime, gyroAngle, wheelPositions);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
index c64ec85cf9b..e5c04e82e19 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java
@@ -62,7 +62,7 @@ public class UnscentedKalmanFilter m_contQ;
private final Matrix m_contR;
private Matrix m_sigmasF;
- private double m_dtSeconds;
+ private double m_dt;
private final MerweScaledSigmaPoints m_pts;
@@ -155,7 +155,7 @@ public UnscentedKalmanFilter(
m_residualFuncY = residualFuncY;
m_addFuncX = addFuncX;
- m_dtSeconds = nominalDtSeconds;
+ m_dt = nominalDtSeconds;
m_contQ = StateSpaceUtil.makeCovarianceMatrix(states, stateStdDevs);
m_contR = StateSpaceUtil.makeCovarianceMatrix(outputs, measurementStdDevs);
@@ -337,14 +337,14 @@ public final void reset() {
* Project the model into the future with a new control input u.
*
* @param u New control input from controller.
- * @param dtSeconds Timestep for prediction.
+ * @param dt Timestep for prediction in seconds.
*/
@Override
- public void predict(Matrix u, double dtSeconds) {
+ public void predict(Matrix u, double dt) {
// Discretize Q before projecting mean and covariance forward
Matrix contA =
NumericalJacobian.numericalJacobianX(m_states, m_states, m_f, m_xHat, u);
- var discQ = Discretization.discretizeAQ(contA, m_contQ, dtSeconds).getSecond();
+ var discQ = Discretization.discretizeAQ(contA, m_contQ, dt).getSecond();
var squareRootDiscQ = discQ.lltDecompose(true);
var sigmas = m_pts.squareRootSigmaPoints(m_xHat, m_S);
@@ -352,7 +352,7 @@ public void predict(Matrix u, double dtSeconds) {
for (int i = 0; i < m_pts.getNumSigmas(); ++i) {
Matrix x = sigmas.extractColumnVector(i);
- m_sigmasF.setColumn(i, NumericalIntegration.rk4(m_f, x, u, dtSeconds));
+ m_sigmasF.setColumn(i, NumericalIntegration.rk4(m_f, x, u, dt));
}
var ret =
@@ -368,7 +368,7 @@ public void predict(Matrix u, double dtSeconds) {
m_xHat = ret.getFirst();
m_S = ret.getSecond();
- m_dtSeconds = dtSeconds;
+ m_dt = dt;
}
/**
@@ -456,7 +456,7 @@ public void correct(
BiFunction, Matrix, Matrix> residualFuncY,
BiFunction, Matrix, Matrix> residualFuncX,
BiFunction, Matrix, Matrix> addFuncX) {
- final var discR = Discretization.discretizeR(R, m_dtSeconds);
+ final var discR = Discretization.discretizeR(R, m_dt);
final var squareRootDiscR = discR.lltDecompose(true);
// Transform sigma points into measurement space
diff --git a/wpimath/src/main/java/edu/wpi/first/math/filter/Debouncer.java b/wpimath/src/main/java/edu/wpi/first/math/filter/Debouncer.java
index 9a281e83f75..5aa38dafe46 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/filter/Debouncer.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/filter/Debouncer.java
@@ -21,11 +21,11 @@ public enum DebounceType {
kBoth
}
- private final double m_debounceTimeSeconds;
+ private final double m_debounceTime;
private final DebounceType m_debounceType;
private boolean m_baseline;
- private double m_prevTimeSeconds;
+ private double m_prevTime;
/**
* Creates a new Debouncer.
@@ -35,7 +35,7 @@ public enum DebounceType {
* @param type Which type of state change the debouncing will be performed on.
*/
public Debouncer(double debounceTime, DebounceType type) {
- m_debounceTimeSeconds = debounceTime;
+ m_debounceTime = debounceTime;
m_debounceType = type;
resetTimer();
@@ -58,11 +58,11 @@ public Debouncer(double debounceTime) {
}
private void resetTimer() {
- m_prevTimeSeconds = MathSharedStore.getTimestamp();
+ m_prevTime = MathSharedStore.getTimestamp();
}
private boolean hasElapsed() {
- return MathSharedStore.getTimestamp() - m_prevTimeSeconds >= m_debounceTimeSeconds;
+ return MathSharedStore.getTimestamp() - m_prevTime >= m_debounceTime;
}
/**
diff --git a/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java b/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
index f9f20c37325..8a06ba8e61e 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/interpolation/TimeInterpolatableBuffer.java
@@ -65,18 +65,18 @@ public static TimeInterpolatableBuffer createDoubleBuffer(double history
/**
* Add a sample to the buffer.
*
- * @param timeSeconds The timestamp of the sample.
+ * @param time The timestamp of the sample in seconds.
* @param sample The sample object.
*/
- public void addSample(double timeSeconds, T sample) {
- cleanUp(timeSeconds);
- m_pastSnapshots.put(timeSeconds, sample);
+ public void addSample(double time, T sample) {
+ cleanUp(time);
+ m_pastSnapshots.put(time, sample);
}
/**
* Removes samples older than our current history size.
*
- * @param time The current timestamp.
+ * @param time The current timestamp in seconds.
*/
private void cleanUp(double time) {
while (!m_pastSnapshots.isEmpty()) {
@@ -97,22 +97,22 @@ public void clear() {
/**
* Sample the buffer at the given time. If the buffer is empty, an empty Optional is returned.
*
- * @param timeSeconds The time at which to sample.
+ * @param time The time at which to sample in seconds.
* @return The interpolated value at that timestamp or an empty Optional.
*/
- public Optional getSample(double timeSeconds) {
+ public Optional getSample(double time) {
if (m_pastSnapshots.isEmpty()) {
return Optional.empty();
}
// Special case for when the requested time is the same as a sample
- var nowEntry = m_pastSnapshots.get(timeSeconds);
+ var nowEntry = m_pastSnapshots.get(time);
if (nowEntry != null) {
return Optional.of(nowEntry);
}
- var topBound = m_pastSnapshots.ceilingEntry(timeSeconds);
- var bottomBound = m_pastSnapshots.floorEntry(timeSeconds);
+ var topBound = m_pastSnapshots.ceilingEntry(time);
+ var bottomBound = m_pastSnapshots.floorEntry(time);
// Return null if neither sample exists, and the opposite bound if the other is null
if (topBound == null && bottomBound == null) {
@@ -129,7 +129,7 @@ public Optional getSample(double timeSeconds) {
m_interpolatingFunc.interpolate(
bottomBound.getValue(),
topBound.getValue(),
- (timeSeconds - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey())));
+ (time - bottomBound.getKey()) / (topBound.getKey() - bottomBound.getKey())));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
index e0eb4077961..8b375538b3d 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/ChassisSpeeds.java
@@ -31,14 +31,14 @@
* will often have all three components.
*/
public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
- /** Velocity along the x-axis. (Fwd is +) */
- public double vxMetersPerSecond;
+ /** Velocity along the x-axis in meters per second. (Fwd is +) */
+ public double vx;
- /** Velocity along the y-axis. (Left is +) */
- public double vyMetersPerSecond;
+ /** Velocity along the y-axis in meters per second. (Left is +) */
+ public double vy;
- /** Represents the angular velocity of the robot frame. (CCW is +) */
- public double omegaRadiansPerSecond;
+ /** Angular velocity of the robot frame in radians per second. (CCW is +) */
+ public double omega;
/** ChassisSpeeds protobuf for serialization. */
public static final ChassisSpeedsProto proto = new ChassisSpeedsProto();
@@ -52,23 +52,22 @@ public ChassisSpeeds() {}
/**
* Constructs a ChassisSpeeds object.
*
- * @param vxMetersPerSecond Forward velocity.
- * @param vyMetersPerSecond Sideways velocity.
- * @param omegaRadiansPerSecond Angular velocity.
+ * @param vx Forward velocity in meters per second.
+ * @param vy Sideways velocity in meters per second.
+ * @param omega Angular velocity in radians per second.
*/
- public ChassisSpeeds(
- double vxMetersPerSecond, double vyMetersPerSecond, double omegaRadiansPerSecond) {
- this.vxMetersPerSecond = vxMetersPerSecond;
- this.vyMetersPerSecond = vyMetersPerSecond;
- this.omegaRadiansPerSecond = omegaRadiansPerSecond;
+ public ChassisSpeeds(double vx, double vy, double omega) {
+ this.vx = vx;
+ this.vy = vy;
+ this.omega = omega;
}
/**
* Constructs a ChassisSpeeds object.
*
- * @param vx Forward velocity.
- * @param vy Sideways velocity.
- * @param omega Angular velocity.
+ * @param vx Forward velocity in meters per second.
+ * @param vy Sideways velocity in meters per second.
+ * @param omega Angular velocity in radians per second.
*/
public ChassisSpeeds(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) {
this(vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond));
@@ -77,14 +76,11 @@ public ChassisSpeeds(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega
/**
* Creates a Twist2d from ChassisSpeeds.
*
- * @param dtSeconds The duration of the timestep.
+ * @param dt The duration of the timestep in seconds.
* @return Twist2d.
*/
- public Twist2d toTwist2d(double dtSeconds) {
- return new Twist2d(
- vxMetersPerSecond * dtSeconds,
- vyMetersPerSecond * dtSeconds,
- omegaRadiansPerSecond * dtSeconds);
+ public Twist2d toTwist2d(double dt) {
+ return new Twist2d(vx * dt, vy * dt, omega * dt);
}
/**
@@ -98,33 +94,25 @@ public Twist2d toTwist2d(double dtSeconds) {
* This is useful for compensating for translational skew when translating and rotating a
* swerve drivetrain.
*
- * @param vxMetersPerSecond Forward velocity.
- * @param vyMetersPerSecond Sideways velocity.
- * @param omegaRadiansPerSecond Angular velocity.
- * @param dtSeconds The duration of the timestep the speeds should be applied for.
+ * @param vx Forward velocity in meters per second.
+ * @param vy Sideways velocity in meters per second.
+ * @param omega Angular velocity in radians per second.
+ * @param dt The duration of the timestep in seconds the speeds should be applied for.
* @return Discretized ChassisSpeeds.
* @deprecated Use instance method instead.
*/
@Deprecated(forRemoval = true, since = "2025")
- public static ChassisSpeeds discretize(
- double vxMetersPerSecond,
- double vyMetersPerSecond,
- double omegaRadiansPerSecond,
- double dtSeconds) {
+ public static ChassisSpeeds discretize(double vx, double vy, double omega, double dt) {
// Construct the desired pose after a timestep, relative to the current pose. The desired pose
// has decoupled translation and rotation.
- var desiredDeltaPose =
- new Pose2d(
- vxMetersPerSecond * dtSeconds,
- vyMetersPerSecond * dtSeconds,
- new Rotation2d(omegaRadiansPerSecond * dtSeconds));
+ var desiredDeltaPose = new Pose2d(vx * dt, vy * dt, new Rotation2d(omega * dt));
// Find the chassis translation/rotation deltas in the robot frame that move the robot from its
// current pose to the desired pose
var twist = Pose2d.kZero.log(desiredDeltaPose);
// Turn the chassis translation/rotation deltas into average velocities
- return new ChassisSpeeds(twist.dx / dtSeconds, twist.dy / dtSeconds, twist.dtheta / dtSeconds);
+ return new ChassisSpeeds(twist.dx / dt, twist.dy / dt, twist.dtheta / dt);
}
/**
@@ -138,10 +126,10 @@ public static ChassisSpeeds discretize(
*
This is useful for compensating for translational skew when translating and rotating a
* swerve drivetrain.
*
- * @param vx Forward velocity.
- * @param vy Sideways velocity.
- * @param omega Angular velocity.
- * @param dt The duration of the timestep the speeds should be applied for.
+ * @param vx Forward velocity in meters per second.
+ * @param vy Sideways velocity in meters per second.
+ * @param omega Angular velocity in radians per second.
+ * @param dt The duration of the timestep in seconds the speeds should be applied for.
* @return Discretized ChassisSpeeds.
* @deprecated Use instance method instead.
*/
@@ -164,17 +152,13 @@ public static ChassisSpeeds discretize(
* swerve drivetrain.
*
* @param continuousSpeeds The continuous speeds.
- * @param dtSeconds The duration of the timestep the speeds should be applied for.
+ * @param dt The duration of the timestep in seconds the speeds should be applied for.
* @return Discretized ChassisSpeeds.
* @deprecated Use instance method instead.
*/
@Deprecated(forRemoval = true, since = "2025")
- public static ChassisSpeeds discretize(ChassisSpeeds continuousSpeeds, double dtSeconds) {
- return discretize(
- continuousSpeeds.vxMetersPerSecond,
- continuousSpeeds.vyMetersPerSecond,
- continuousSpeeds.omegaRadiansPerSecond,
- dtSeconds);
+ public static ChassisSpeeds discretize(ChassisSpeeds continuousSpeeds, double dt) {
+ return discretize(continuousSpeeds.vx, continuousSpeeds.vy, continuousSpeeds.omega, dt);
}
/**
@@ -188,34 +172,30 @@ public static ChassisSpeeds discretize(ChassisSpeeds continuousSpeeds, double dt
*
This is useful for compensating for translational skew when translating and rotating a
* swerve drivetrain.
*
- * @param dtSeconds The duration of the timestep the speeds should be applied for.
+ * @param dt The duration of the timestep in seconds the speeds should be applied for.
*/
- public void discretize(double dtSeconds) {
- var desiredDeltaPose =
- new Pose2d(
- vxMetersPerSecond * dtSeconds,
- vyMetersPerSecond * dtSeconds,
- new Rotation2d(omegaRadiansPerSecond * dtSeconds));
+ public void discretize(double dt) {
+ var desiredDeltaPose = new Pose2d(vx * dt, vy * dt, new Rotation2d(omega * dt));
// Find the chassis translation/rotation deltas in the robot frame that move the robot from its
// current pose to the desired pose
var twist = Pose2d.kZero.log(desiredDeltaPose);
// Turn the chassis translation/rotation deltas into average velocities
- vxMetersPerSecond = twist.dx / dtSeconds;
- vyMetersPerSecond = twist.dy / dtSeconds;
- omegaRadiansPerSecond = twist.dtheta / dtSeconds;
+ vx = twist.dx / dt;
+ vy = twist.dy / dt;
+ omega = twist.dtheta / dt;
}
/**
* Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds
* object.
*
- * @param vxMetersPerSecond The component of speed in the x direction relative to the field.
- * Positive x is away from your alliance wall.
- * @param vyMetersPerSecond The component of speed in the y direction relative to the field.
- * Positive y is to your left when standing behind the alliance wall.
- * @param omegaRadiansPerSecond The angular rate of the robot.
+ * @param vx The component of speed in the x direction relative to the field, in meters per
+ * second. Positive x is away from your alliance wall.
+ * @param vy The component of speed in the y direction relative to the field, in meters per
+ * second. Positive y is to your left when standing behind the alliance wall.
+ * @param omega The angular rate of the robot in radians per second.
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
* considered to be zero when it is facing directly away from your alliance station wall.
* Remember that this should be CCW positive.
@@ -224,25 +204,21 @@ public void discretize(double dtSeconds) {
*/
@Deprecated(forRemoval = true, since = "2025")
public static ChassisSpeeds fromFieldRelativeSpeeds(
- double vxMetersPerSecond,
- double vyMetersPerSecond,
- double omegaRadiansPerSecond,
- Rotation2d robotAngle) {
+ double vx, double vy, double omega, Rotation2d robotAngle) {
// CW rotation into chassis frame
- var rotated =
- new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle.unaryMinus());
- return new ChassisSpeeds(rotated.getX(), rotated.getY(), omegaRadiansPerSecond);
+ var rotated = new Translation2d(vx, vy).rotateBy(robotAngle.unaryMinus());
+ return new ChassisSpeeds(rotated.getX(), rotated.getY(), omega);
}
/**
* Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds
* object.
*
- * @param vx The component of speed in the x direction relative to the field. Positive x is away
- * from your alliance wall.
- * @param vy The component of speed in the y direction relative to the field. Positive y is to
- * your left when standing behind the alliance wall.
- * @param omega The angular rate of the robot.
+ * @param vx The component of speed in the x direction relative to the field, in meters per
+ * second. Positive x is away from your alliance wall.
+ * @param vy The component of speed in the y direction relative to the field, in meters per
+ * second. Positive y is to your left when standing behind the alliance wall.
+ * @param omega The angular rate of the robot in radians per second.
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
* considered to be zero when it is facing directly away from your alliance station wall.
* Remember that this should be CCW positive.
@@ -273,10 +249,7 @@ public static ChassisSpeeds fromFieldRelativeSpeeds(
public static ChassisSpeeds fromFieldRelativeSpeeds(
ChassisSpeeds fieldRelativeSpeeds, Rotation2d robotAngle) {
return fromFieldRelativeSpeeds(
- fieldRelativeSpeeds.vxMetersPerSecond,
- fieldRelativeSpeeds.vyMetersPerSecond,
- fieldRelativeSpeeds.omegaRadiansPerSecond,
- robotAngle);
+ fieldRelativeSpeeds.vx, fieldRelativeSpeeds.vy, fieldRelativeSpeeds.omega, robotAngle);
}
/**
@@ -288,21 +261,20 @@ public static ChassisSpeeds fromFieldRelativeSpeeds(
*/
public void toRobotRelativeSpeeds(Rotation2d robotAngle) {
// CW rotation into chassis frame
- var rotated =
- new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle.unaryMinus());
- vxMetersPerSecond = rotated.getX();
- vyMetersPerSecond = rotated.getY();
+ var rotated = new Translation2d(vx, vy).rotateBy(robotAngle.unaryMinus());
+ vx = rotated.getX();
+ vy = rotated.getY();
}
/**
* Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds
* object.
*
- * @param vxMetersPerSecond The component of speed in the x direction relative to the robot.
- * Positive x is towards the robot's front.
- * @param vyMetersPerSecond The component of speed in the y direction relative to the robot.
- * Positive y is towards the robot's left.
- * @param omegaRadiansPerSecond The angular rate of the robot.
+ * @param vx The component of speed in the x direction relative to the robot, in meters per
+ * second. Positive x is towards the robot's front.
+ * @param vy The component of speed in the y direction relative to the robot, in meters per
+ * second. Positive y is towards the robot's left.
+ * @param omega The angular rate of the robot in radians per second.
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
* considered to be zero when it is facing directly away from your alliance station wall.
* Remember that this should be CCW positive.
@@ -311,24 +283,21 @@ public void toRobotRelativeSpeeds(Rotation2d robotAngle) {
*/
@Deprecated(forRemoval = true, since = "2025")
public static ChassisSpeeds fromRobotRelativeSpeeds(
- double vxMetersPerSecond,
- double vyMetersPerSecond,
- double omegaRadiansPerSecond,
- Rotation2d robotAngle) {
+ double vx, double vy, double omega, Rotation2d robotAngle) {
// CCW rotation out of chassis frame
- var rotated = new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle);
- return new ChassisSpeeds(rotated.getX(), rotated.getY(), omegaRadiansPerSecond);
+ var rotated = new Translation2d(vx, vy).rotateBy(robotAngle);
+ return new ChassisSpeeds(rotated.getX(), rotated.getY(), omega);
}
/**
* Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds
* object.
*
- * @param vx The component of speed in the x direction relative to the robot. Positive x is
- * towards the robot's front.
- * @param vy The component of speed in the y direction relative to the robot. Positive y is
- * towards the robot's left.
- * @param omega The angular rate of the robot.
+ * @param vx The component of speed in the x direction relative to the robot, in meters per
+ * second. Positive x is towards the robot's front.
+ * @param vy The component of speed in the y direction relative to the robot, in meters per
+ * second. Positive y is towards the robot's left.
+ * @param omega The angular rate of the robot in radians per second.
* @param robotAngle The angle of the robot as measured by a gyroscope. The robot's angle is
* considered to be zero when it is facing directly away from your alliance station wall.
* Remember that this should be CCW positive.
@@ -359,10 +328,7 @@ public static ChassisSpeeds fromRobotRelativeSpeeds(
public static ChassisSpeeds fromRobotRelativeSpeeds(
ChassisSpeeds robotRelativeSpeeds, Rotation2d robotAngle) {
return fromRobotRelativeSpeeds(
- robotRelativeSpeeds.vxMetersPerSecond,
- robotRelativeSpeeds.vyMetersPerSecond,
- robotRelativeSpeeds.omegaRadiansPerSecond,
- robotAngle);
+ robotRelativeSpeeds.vx, robotRelativeSpeeds.vy, robotRelativeSpeeds.omega, robotAngle);
}
/**
@@ -374,9 +340,9 @@ public static ChassisSpeeds fromRobotRelativeSpeeds(
*/
public void toFieldRelativeSpeeds(Rotation2d robotAngle) {
// CCW rotation out of chassis frame
- var rotated = new Translation2d(vxMetersPerSecond, vyMetersPerSecond).rotateBy(robotAngle);
- vxMetersPerSecond = rotated.getX();
- vyMetersPerSecond = rotated.getY();
+ var rotated = new Translation2d(vx, vy).rotateBy(robotAngle);
+ vx = rotated.getX();
+ vy = rotated.getY();
}
/**
@@ -389,10 +355,7 @@ public void toFieldRelativeSpeeds(Rotation2d robotAngle) {
* @return The sum of the ChassisSpeeds.
*/
public ChassisSpeeds plus(ChassisSpeeds other) {
- return new ChassisSpeeds(
- vxMetersPerSecond + other.vxMetersPerSecond,
- vyMetersPerSecond + other.vyMetersPerSecond,
- omegaRadiansPerSecond + other.omegaRadiansPerSecond);
+ return new ChassisSpeeds(vx + other.vx, vy + other.vy, omega + other.omega);
}
/**
@@ -405,10 +368,7 @@ public ChassisSpeeds plus(ChassisSpeeds other) {
* @return The difference between the two ChassisSpeeds.
*/
public ChassisSpeeds minus(ChassisSpeeds other) {
- return new ChassisSpeeds(
- vxMetersPerSecond - other.vxMetersPerSecond,
- vyMetersPerSecond - other.vyMetersPerSecond,
- omegaRadiansPerSecond - other.omegaRadiansPerSecond);
+ return new ChassisSpeeds(vx - other.vx, vy - other.vy, omega - other.omega);
}
/**
@@ -418,7 +378,7 @@ public ChassisSpeeds minus(ChassisSpeeds other) {
* @return The inverse of the current ChassisSpeeds.
*/
public ChassisSpeeds unaryMinus() {
- return new ChassisSpeeds(-vxMetersPerSecond, -vyMetersPerSecond, -omegaRadiansPerSecond);
+ return new ChassisSpeeds(-vx, -vy, -omega);
}
/**
@@ -430,8 +390,7 @@ public ChassisSpeeds unaryMinus() {
* @return The scaled ChassisSpeeds.
*/
public ChassisSpeeds times(double scalar) {
- return new ChassisSpeeds(
- vxMetersPerSecond * scalar, vyMetersPerSecond * scalar, omegaRadiansPerSecond * scalar);
+ return new ChassisSpeeds(vx * scalar, vy * scalar, omega * scalar);
}
/**
@@ -443,28 +402,23 @@ public ChassisSpeeds times(double scalar) {
* @return The scaled ChassisSpeeds.
*/
public ChassisSpeeds div(double scalar) {
- return new ChassisSpeeds(
- vxMetersPerSecond / scalar, vyMetersPerSecond / scalar, omegaRadiansPerSecond / scalar);
+ return new ChassisSpeeds(vx / scalar, vy / scalar, omega / scalar);
}
@Override
public final int hashCode() {
- return Objects.hash(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
+ return Objects.hash(vx, vy, omega);
}
@Override
public boolean equals(Object o) {
return o == this
- || o instanceof ChassisSpeeds c
- && vxMetersPerSecond == c.vxMetersPerSecond
- && vyMetersPerSecond == c.vyMetersPerSecond
- && omegaRadiansPerSecond == c.omegaRadiansPerSecond;
+ || o instanceof ChassisSpeeds c && vx == c.vx && vy == c.vy && omega == c.omega;
}
@Override
public String toString() {
return String.format(
- "ChassisSpeeds(Vx: %.2f m/s, Vy: %.2f m/s, Omega: %.2f rad/s)",
- vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
+ "ChassisSpeeds(Vx: %.2f m/s, Vy: %.2f m/s, Omega: %.2f rad/s)", vx, vy, omega);
}
}
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 ffa24cd9ba9..766a0522b55 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
@@ -27,8 +27,8 @@ public class DifferentialDriveKinematics
implements Kinematics,
ProtobufSerializable,
StructSerializable {
- /** Differential drive trackwidth. */
- public final double trackWidthMeters;
+ /** Differential drive trackwidth in meters. */
+ public final double trackwidth;
/** DifferentialDriveKinematics protobuf for serialization. */
public static final DifferentialDriveKinematicsProto proto =
@@ -41,24 +41,24 @@ public class DifferentialDriveKinematics
/**
* Constructs a differential drive kinematics object.
*
- * @param trackWidthMeters The track width of the drivetrain. Theoretically, this is the distance
- * between the left wheels and right wheels. However, the empirical value may be larger than
- * the physical measured value due to scrubbing effects.
+ * @param trackwidth The trackwidth of the drivetrain in meters. Theoretically, this is the
+ * distance between the left wheels and right wheels. However, the empirical value may be
+ * larger than the physical measured value due to scrubbing effects.
*/
- public DifferentialDriveKinematics(double trackWidthMeters) {
- this.trackWidthMeters = trackWidthMeters;
+ public DifferentialDriveKinematics(double trackwidth) {
+ this.trackwidth = trackwidth;
MathSharedStore.reportUsage(MathUsageId.kKinematics_DifferentialDrive, 1);
}
/**
* Constructs a differential drive kinematics object.
*
- * @param trackWidth The track width of the drivetrain. Theoretically, this is the distance
- * between the left wheels and right wheels. However, the empirical value may be larger than
- * the physical measured value due to scrubbing effects.
+ * @param trackwidth The trackwidth of the drivetrain in meters. Theoretically, this is the
+ * distance between the left wheels and right wheels. However, the empirical value may be
+ * larger than the physical measured value due to scrubbing effects.
*/
- public DifferentialDriveKinematics(Distance trackWidth) {
- this(trackWidth.in(Meters));
+ public DifferentialDriveKinematics(Distance trackwidth) {
+ this(trackwidth.in(Meters));
}
/**
@@ -70,9 +70,9 @@ public DifferentialDriveKinematics(Distance trackWidth) {
@Override
public ChassisSpeeds toChassisSpeeds(DifferentialDriveWheelSpeeds wheelSpeeds) {
return new ChassisSpeeds(
- (wheelSpeeds.leftMetersPerSecond + wheelSpeeds.rightMetersPerSecond) / 2,
+ (wheelSpeeds.left + wheelSpeeds.right) / 2,
0,
- (wheelSpeeds.rightMetersPerSecond - wheelSpeeds.leftMetersPerSecond) / trackWidthMeters);
+ (wheelSpeeds.right - wheelSpeeds.left) / trackwidth);
}
/**
@@ -85,16 +85,14 @@ public ChassisSpeeds toChassisSpeeds(DifferentialDriveWheelSpeeds wheelSpeeds) {
@Override
public DifferentialDriveWheelSpeeds toWheelSpeeds(ChassisSpeeds chassisSpeeds) {
return new DifferentialDriveWheelSpeeds(
- chassisSpeeds.vxMetersPerSecond
- - trackWidthMeters / 2 * chassisSpeeds.omegaRadiansPerSecond,
- chassisSpeeds.vxMetersPerSecond
- + trackWidthMeters / 2 * chassisSpeeds.omegaRadiansPerSecond);
+ chassisSpeeds.vx - trackwidth / 2 * chassisSpeeds.omega,
+ chassisSpeeds.vx + trackwidth / 2 * chassisSpeeds.omega);
}
@Override
public Twist2d toTwist2d(
DifferentialDriveWheelPositions start, DifferentialDriveWheelPositions end) {
- return toTwist2d(end.leftMeters - start.leftMeters, end.rightMeters - start.rightMeters);
+ return toTwist2d(end.left - start.left, end.right - start.right);
}
/**
@@ -102,27 +100,25 @@ public Twist2d toTwist2d(
* distance deltas. This method is often used for odometry -- determining the robot's position on
* the field using changes in the distance driven by each wheel on the robot.
*
- * @param leftDistanceMeters The distance measured by the left side encoder.
- * @param rightDistanceMeters The distance measured by the right side encoder.
+ * @param leftDistance The distance measured by the left side encoder.
+ * @param rightDistance The distance measured by the right side encoder.
* @return The resulting Twist2d.
*/
- public Twist2d toTwist2d(double leftDistanceMeters, double rightDistanceMeters) {
+ public Twist2d toTwist2d(double leftDistance, double rightDistance) {
return new Twist2d(
- (leftDistanceMeters + rightDistanceMeters) / 2,
- 0,
- (rightDistanceMeters - leftDistanceMeters) / trackWidthMeters);
+ (leftDistance + rightDistance) / 2, 0, (rightDistance - leftDistance) / trackwidth);
}
@Override
public DifferentialDriveWheelPositions copy(DifferentialDriveWheelPositions positions) {
- return new DifferentialDriveWheelPositions(positions.leftMeters, positions.rightMeters);
+ return new DifferentialDriveWheelPositions(positions.left, positions.right);
}
@Override
public void copyInto(
DifferentialDriveWheelPositions positions, DifferentialDriveWheelPositions output) {
- output.leftMeters = positions.leftMeters;
- output.rightMeters = positions.rightMeters;
+ output.left = positions.left;
+ output.right = positions.right;
}
@Override
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
index 46fb3950638..98aed4e4473 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java
@@ -27,20 +27,17 @@ public class DifferentialDriveOdometry extends Odometry {
- /** Distance measured by the left side. */
- public double leftMeters;
+ /** Distance measured by the left side in meters. */
+ public double left;
- /** Distance measured by the right side. */
- public double rightMeters;
+ /** Distance measured by the right side in meters. */
+ public double right;
/** DifferentialDriveWheelPositions struct for serialization. */
public static final DifferentialDriveWheelPositionsStruct struct =
@@ -33,19 +33,19 @@ public class DifferentialDriveWheelPositions
/**
* Constructs a DifferentialDriveWheelPositions.
*
- * @param leftMeters Distance measured by the left side.
- * @param rightMeters Distance measured by the right side.
+ * @param left Distance measured by the left side in meters.
+ * @param right Distance measured by the right side in meters.
*/
- public DifferentialDriveWheelPositions(double leftMeters, double rightMeters) {
- this.leftMeters = leftMeters;
- this.rightMeters = rightMeters;
+ public DifferentialDriveWheelPositions(double left, double right) {
+ this.left = left;
+ this.right = right;
}
/**
* Constructs a DifferentialDriveWheelPositions.
*
- * @param left Distance measured by the left side.
- * @param right Distance measured by the right side.
+ * @param left Distance measured by the left side in meters.
+ * @param right Distance measured by the right side in meters.
*/
public DifferentialDriveWheelPositions(Distance left, Distance right) {
this(left.in(Meters), right.in(Meters));
@@ -54,26 +54,26 @@ public DifferentialDriveWheelPositions(Distance left, Distance right) {
@Override
public boolean equals(Object obj) {
return obj instanceof DifferentialDriveWheelPositions other
- && Math.abs(other.leftMeters - leftMeters) < 1E-9
- && Math.abs(other.rightMeters - rightMeters) < 1E-9;
+ && Math.abs(other.left - left) < 1E-9
+ && Math.abs(other.right - right) < 1E-9;
}
@Override
public int hashCode() {
- return Objects.hash(leftMeters, rightMeters);
+ return Objects.hash(left, right);
}
@Override
public String toString() {
return String.format(
- "DifferentialDriveWheelPositions(Left: %.2f m, Right: %.2f m", leftMeters, rightMeters);
+ "DifferentialDriveWheelPositions(Left: %.2f m, Right: %.2f m", left, right);
}
@Override
public DifferentialDriveWheelPositions interpolate(
DifferentialDriveWheelPositions endValue, double t) {
return new DifferentialDriveWheelPositions(
- MathUtil.interpolate(this.leftMeters, endValue.leftMeters, t),
- MathUtil.interpolate(this.rightMeters, endValue.rightMeters, t));
+ MathUtil.interpolate(this.left, endValue.left, t),
+ MathUtil.interpolate(this.right, endValue.right, t));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
index 6796fabb1e2..60b3bca8f35 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveWheelSpeeds.java
@@ -14,11 +14,11 @@
/** Represents the wheel speeds for a differential drive drivetrain. */
public class DifferentialDriveWheelSpeeds implements ProtobufSerializable, StructSerializable {
- /** Speed of the left side of the robot. */
- public double leftMetersPerSecond;
+ /** Speed of the left side of the robot in meters per second. */
+ public double left;
- /** Speed of the right side of the robot. */
- public double rightMetersPerSecond;
+ /** Speed of the right side of the robot in meters per second. */
+ public double right;
/** DifferentialDriveWheelSpeeds protobuf for serialization. */
public static final DifferentialDriveWheelSpeedsProto proto =
@@ -34,19 +34,19 @@ public DifferentialDriveWheelSpeeds() {}
/**
* Constructs a DifferentialDriveWheelSpeeds.
*
- * @param leftMetersPerSecond The left speed.
- * @param rightMetersPerSecond The right speed.
+ * @param left The left speed in meters per second.
+ * @param right The right speed in meters per second.
*/
- public DifferentialDriveWheelSpeeds(double leftMetersPerSecond, double rightMetersPerSecond) {
- this.leftMetersPerSecond = leftMetersPerSecond;
- this.rightMetersPerSecond = rightMetersPerSecond;
+ public DifferentialDriveWheelSpeeds(double left, double right) {
+ this.left = left;
+ this.right = right;
}
/**
* Constructs a DifferentialDriveWheelSpeeds.
*
- * @param left The left speed.
- * @param right The right speed.
+ * @param left The left speed in meters per second.
+ * @param right The right speed in meters per second.
*/
public DifferentialDriveWheelSpeeds(LinearVelocity left, LinearVelocity right) {
this(left.in(MetersPerSecond), right.in(MetersPerSecond));
@@ -60,15 +60,14 @@ public DifferentialDriveWheelSpeeds(LinearVelocity left, LinearVelocity right) {
* reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
* absolute threshold, while maintaining the ratio of speeds between wheels.
*
- * @param attainableMaxSpeedMetersPerSecond The absolute max speed that a wheel can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a wheel can reach.
*/
- public void desaturate(double attainableMaxSpeedMetersPerSecond) {
- double realMaxSpeed = Math.max(Math.abs(leftMetersPerSecond), Math.abs(rightMetersPerSecond));
+ public void desaturate(double attainableMaxSpeed) {
+ double realMaxSpeed = Math.max(Math.abs(left), Math.abs(right));
- if (realMaxSpeed > attainableMaxSpeedMetersPerSecond) {
- leftMetersPerSecond = leftMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
- rightMetersPerSecond =
- rightMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
+ if (realMaxSpeed > attainableMaxSpeed) {
+ left = left / realMaxSpeed * attainableMaxSpeed;
+ right = right / realMaxSpeed * attainableMaxSpeed;
}
}
@@ -80,7 +79,7 @@ public void desaturate(double attainableMaxSpeedMetersPerSecond) {
* reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
* absolute threshold, while maintaining the ratio of speeds between wheels.
*
- * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a wheel can reach.
*/
public void desaturate(LinearVelocity attainableMaxSpeed) {
desaturate(attainableMaxSpeed.in(MetersPerSecond));
@@ -96,9 +95,7 @@ public void desaturate(LinearVelocity attainableMaxSpeed) {
* @return The sum of the DifferentialDriveWheelSpeeds.
*/
public DifferentialDriveWheelSpeeds plus(DifferentialDriveWheelSpeeds other) {
- return new DifferentialDriveWheelSpeeds(
- leftMetersPerSecond + other.leftMetersPerSecond,
- rightMetersPerSecond + other.rightMetersPerSecond);
+ return new DifferentialDriveWheelSpeeds(left + other.left, right + other.right);
}
/**
@@ -112,9 +109,7 @@ public DifferentialDriveWheelSpeeds plus(DifferentialDriveWheelSpeeds other) {
* @return The difference between the two DifferentialDriveWheelSpeeds.
*/
public DifferentialDriveWheelSpeeds minus(DifferentialDriveWheelSpeeds other) {
- return new DifferentialDriveWheelSpeeds(
- leftMetersPerSecond - other.leftMetersPerSecond,
- rightMetersPerSecond - other.rightMetersPerSecond);
+ return new DifferentialDriveWheelSpeeds(left - other.left, right - other.right);
}
/**
@@ -124,7 +119,7 @@ public DifferentialDriveWheelSpeeds minus(DifferentialDriveWheelSpeeds other) {
* @return The inverse of the current DifferentialDriveWheelSpeeds.
*/
public DifferentialDriveWheelSpeeds unaryMinus() {
- return new DifferentialDriveWheelSpeeds(-leftMetersPerSecond, -rightMetersPerSecond);
+ return new DifferentialDriveWheelSpeeds(-left, -right);
}
/**
@@ -138,8 +133,7 @@ public DifferentialDriveWheelSpeeds unaryMinus() {
* @return The scaled DifferentialDriveWheelSpeeds.
*/
public DifferentialDriveWheelSpeeds times(double scalar) {
- return new DifferentialDriveWheelSpeeds(
- leftMetersPerSecond * scalar, rightMetersPerSecond * scalar);
+ return new DifferentialDriveWheelSpeeds(left * scalar, right * scalar);
}
/**
@@ -153,14 +147,12 @@ public DifferentialDriveWheelSpeeds times(double scalar) {
* @return The scaled DifferentialDriveWheelSpeeds.
*/
public DifferentialDriveWheelSpeeds div(double scalar) {
- return new DifferentialDriveWheelSpeeds(
- leftMetersPerSecond / scalar, rightMetersPerSecond / scalar);
+ return new DifferentialDriveWheelSpeeds(left / scalar, right / scalar);
}
@Override
public String toString() {
return String.format(
- "DifferentialDriveWheelSpeeds(Left: %.2f m/s, Right: %.2f m/s)",
- leftMetersPerSecond, rightMetersPerSecond);
+ "DifferentialDriveWheelSpeeds(Left: %.2f m/s, Right: %.2f m/s)", left, right);
}
}
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 0135af24d61..ac8fda8884f 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
@@ -41,10 +41,10 @@ public class MecanumDriveKinematics
private final SimpleMatrix m_inverseKinematics;
private final SimpleMatrix m_forwardKinematics;
- private final Translation2d m_frontLeftWheelMeters;
- private final Translation2d m_frontRightWheelMeters;
- private final Translation2d m_rearLeftWheelMeters;
- private final Translation2d m_rearRightWheelMeters;
+ private final Translation2d m_frontLeftWheel;
+ private final Translation2d m_frontRightWheel;
+ private final Translation2d m_rearLeftWheel;
+ private final Translation2d m_rearRightWheel;
private Translation2d m_prevCoR = Translation2d.kZero;
@@ -57,29 +57,28 @@ public class MecanumDriveKinematics
/**
* Constructs a mecanum drive kinematics object.
*
- * @param frontLeftWheelMeters The location of the front-left wheel relative to the physical
- * center of the robot.
- * @param frontRightWheelMeters The location of the front-right wheel relative to the physical
- * center of the robot.
- * @param rearLeftWheelMeters The location of the rear-left wheel relative to the physical center
- * of the robot.
- * @param rearRightWheelMeters The location of the rear-right wheel relative to the physical
- * center of the robot.
+ * @param frontLeftWheel The location of the front-left wheel relative to the physical center of
+ * the robot, in meters.
+ * @param frontRightWheel The location of the front-right wheel relative to the physical center of
+ * the robot, in meters.
+ * @param rearLeftWheel The location of the rear-left wheel relative to the physical center of the
+ * robot, in meters.
+ * @param rearRightWheel The location of the rear-right wheel relative to the physical center of
+ * the robot, in meters.
*/
public MecanumDriveKinematics(
- Translation2d frontLeftWheelMeters,
- Translation2d frontRightWheelMeters,
- Translation2d rearLeftWheelMeters,
- Translation2d rearRightWheelMeters) {
- m_frontLeftWheelMeters = frontLeftWheelMeters;
- m_frontRightWheelMeters = frontRightWheelMeters;
- m_rearLeftWheelMeters = rearLeftWheelMeters;
- m_rearRightWheelMeters = rearRightWheelMeters;
+ Translation2d frontLeftWheel,
+ Translation2d frontRightWheel,
+ Translation2d rearLeftWheel,
+ Translation2d rearRightWheel) {
+ m_frontLeftWheel = frontLeftWheel;
+ m_frontRightWheel = frontRightWheel;
+ m_rearLeftWheel = rearLeftWheel;
+ m_rearRightWheel = rearRightWheel;
m_inverseKinematics = new SimpleMatrix(4, 3);
- setInverseKinematics(
- frontLeftWheelMeters, frontRightWheelMeters, rearLeftWheelMeters, rearRightWheelMeters);
+ setInverseKinematics(frontLeftWheel, frontRightWheel, rearLeftWheel, rearRightWheel);
m_forwardKinematics = m_inverseKinematics.pseudoInverse();
MathSharedStore.reportUsage(MathUsageId.kKinematics_MecanumDrive, 1);
@@ -95,33 +94,28 @@ public MecanumDriveKinematics(
* for evasive maneuvers, vision alignment, or for any other use case, you can do so.
*
* @param chassisSpeeds The desired chassis speed.
- * @param centerOfRotationMeters The center of rotation. For example, if you set the center of
- * rotation at one corner of the robot and provide a chassis speed that only has a dtheta
- * component, the robot will rotate around that corner.
+ * @param centerOfRotation The center of rotation. For example, if you set the center of rotation
+ * at one corner of the robot and provide a chassis speed that only has a dtheta component,
+ * the robot will rotate around that corner.
* @return The wheel speeds. Use caution because they are not normalized. Sometimes, a user input
* may cause one of the wheel speeds to go above the attainable max velocity. Use the {@link
* MecanumDriveWheelSpeeds#desaturate(double)} function to rectify this issue.
*/
public MecanumDriveWheelSpeeds toWheelSpeeds(
- ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) {
+ ChassisSpeeds chassisSpeeds, Translation2d centerOfRotation) {
// We have a new center of rotation. We need to compute the matrix again.
- if (!centerOfRotationMeters.equals(m_prevCoR)) {
- var fl = m_frontLeftWheelMeters.minus(centerOfRotationMeters);
- var fr = m_frontRightWheelMeters.minus(centerOfRotationMeters);
- var rl = m_rearLeftWheelMeters.minus(centerOfRotationMeters);
- var rr = m_rearRightWheelMeters.minus(centerOfRotationMeters);
+ if (!centerOfRotation.equals(m_prevCoR)) {
+ var fl = m_frontLeftWheel.minus(centerOfRotation);
+ var fr = m_frontRightWheel.minus(centerOfRotation);
+ var rl = m_rearLeftWheel.minus(centerOfRotation);
+ var rr = m_rearRightWheel.minus(centerOfRotation);
setInverseKinematics(fl, fr, rl, rr);
- m_prevCoR = centerOfRotationMeters;
+ m_prevCoR = centerOfRotation;
}
var chassisSpeedsVector = new SimpleMatrix(3, 1);
- chassisSpeedsVector.setColumn(
- 0,
- 0,
- chassisSpeeds.vxMetersPerSecond,
- chassisSpeeds.vyMetersPerSecond,
- chassisSpeeds.omegaRadiansPerSecond);
+ chassisSpeedsVector.setColumn(0, 0, chassisSpeeds.vx, chassisSpeeds.vy, chassisSpeeds.omega);
var wheelsVector = m_inverseKinematics.mult(chassisSpeedsVector);
return new MecanumDriveWheelSpeeds(
@@ -157,10 +151,10 @@ public ChassisSpeeds toChassisSpeeds(MecanumDriveWheelSpeeds wheelSpeeds) {
wheelSpeedsVector.setColumn(
0,
0,
- wheelSpeeds.frontLeftMetersPerSecond,
- wheelSpeeds.frontRightMetersPerSecond,
- wheelSpeeds.rearLeftMetersPerSecond,
- wheelSpeeds.rearRightMetersPerSecond);
+ wheelSpeeds.frontLeft,
+ wheelSpeeds.frontRight,
+ wheelSpeeds.rearLeft,
+ wheelSpeeds.rearRight);
var chassisSpeedsVector = m_forwardKinematics.mult(wheelSpeedsVector);
return new ChassisSpeeds(
@@ -175,10 +169,10 @@ public Twist2d toTwist2d(MecanumDriveWheelPositions start, MecanumDriveWheelPosi
wheelDeltasVector.setColumn(
0,
0,
- end.frontLeftMeters - start.frontLeftMeters,
- end.frontRightMeters - start.frontRightMeters,
- end.rearLeftMeters - start.rearLeftMeters,
- end.rearRightMeters - start.rearRightMeters);
+ end.frontLeft - start.frontLeft,
+ end.frontRight - start.frontRight,
+ end.rearLeft - start.rearLeft,
+ end.rearRight - start.rearRight);
var twist = m_forwardKinematics.mult(wheelDeltasVector);
return new Twist2d(twist.get(0, 0), twist.get(1, 0), twist.get(2, 0));
}
@@ -196,10 +190,10 @@ public Twist2d toTwist2d(MecanumDriveWheelPositions wheelDeltas) {
wheelDeltasVector.setColumn(
0,
0,
- wheelDeltas.frontLeftMeters,
- wheelDeltas.frontRightMeters,
- wheelDeltas.rearLeftMeters,
- wheelDeltas.rearRightMeters);
+ wheelDeltas.frontLeft,
+ wheelDeltas.frontRight,
+ wheelDeltas.rearLeft,
+ wheelDeltas.rearRight);
var twist = m_forwardKinematics.mult(wheelDeltasVector);
return new Twist2d(twist.get(0, 0), twist.get(1, 0), twist.get(2, 0));
}
@@ -226,7 +220,7 @@ private void setInverseKinematics(
* @return The front-left wheel translation.
*/
public Translation2d getFrontLeft() {
- return m_frontLeftWheelMeters;
+ return m_frontLeftWheel;
}
/**
@@ -235,7 +229,7 @@ public Translation2d getFrontLeft() {
* @return The front-right wheel translation.
*/
public Translation2d getFrontRight() {
- return m_frontRightWheelMeters;
+ return m_frontRightWheel;
}
/**
@@ -244,7 +238,7 @@ public Translation2d getFrontRight() {
* @return The rear-left wheel translation.
*/
public Translation2d getRearLeft() {
- return m_rearLeftWheelMeters;
+ return m_rearLeftWheel;
}
/**
@@ -253,24 +247,21 @@ public Translation2d getRearLeft() {
* @return The rear-right wheel translation.
*/
public Translation2d getRearRight() {
- return m_rearRightWheelMeters;
+ return m_rearRightWheel;
}
@Override
public MecanumDriveWheelPositions copy(MecanumDriveWheelPositions positions) {
return new MecanumDriveWheelPositions(
- positions.frontLeftMeters,
- positions.frontRightMeters,
- positions.rearLeftMeters,
- positions.rearRightMeters);
+ positions.frontLeft, positions.frontRight, positions.rearLeft, positions.rearRight);
}
@Override
public void copyInto(MecanumDriveWheelPositions positions, MecanumDriveWheelPositions output) {
- output.frontLeftMeters = positions.frontLeftMeters;
- output.frontRightMeters = positions.frontRightMeters;
- output.rearLeftMeters = positions.rearLeftMeters;
- output.rearRightMeters = positions.rearRightMeters;
+ output.frontLeft = positions.frontLeft;
+ output.frontRight = positions.frontRight;
+ output.rearLeft = positions.rearLeft;
+ output.rearRight = positions.rearRight;
}
@Override
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
index 8bc91b1d8e6..06882d6c3d9 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveMotorVoltages.java
@@ -12,16 +12,16 @@
/** Represents the motor voltages for a mecanum drive drivetrain. */
public class MecanumDriveMotorVoltages implements ProtobufSerializable, StructSerializable {
/** Voltage of the front left motor. */
- public double frontLeftVoltage;
+ public double frontLeft;
/** Voltage of the front right motor. */
- public double frontRightVoltage;
+ public double frontRight;
/** Voltage of the rear left motor. */
- public double rearLeftVoltage;
+ public double rearLeft;
/** Voltage of the rear right motor. */
- public double rearRightVoltage;
+ public double rearRight;
/** Constructs a MecanumDriveMotorVoltages with zeros for all member fields. */
public MecanumDriveMotorVoltages() {}
@@ -29,20 +29,17 @@ public MecanumDriveMotorVoltages() {}
/**
* Constructs a MecanumDriveMotorVoltages.
*
- * @param frontLeftVoltage Voltage of the front left motor.
- * @param frontRightVoltage Voltage of the front right motor.
- * @param rearLeftVoltage Voltage of the rear left motor.
- * @param rearRightVoltage Voltage of the rear right motor.
+ * @param frontLeft Voltage of the front left motor.
+ * @param frontRight Voltage of the front right motor.
+ * @param rearLeft Voltage of the rear left motor.
+ * @param rearRight Voltage of the rear right motor.
*/
public MecanumDriveMotorVoltages(
- double frontLeftVoltage,
- double frontRightVoltage,
- double rearLeftVoltage,
- double rearRightVoltage) {
- this.frontLeftVoltage = frontLeftVoltage;
- this.frontRightVoltage = frontRightVoltage;
- this.rearLeftVoltage = rearLeftVoltage;
- this.rearRightVoltage = rearRightVoltage;
+ double frontLeft, double frontRight, double rearLeft, double rearRight) {
+ this.frontLeft = frontLeft;
+ this.frontRight = frontRight;
+ this.rearLeft = rearLeft;
+ this.rearRight = rearRight;
}
@Override
@@ -50,7 +47,7 @@ public String toString() {
return String.format(
"MecanumDriveMotorVoltages(Front Left: %.2f V, Front Right: %.2f V, "
+ "Rear Left: %.2f V, Rear Right: %.2f V)",
- frontLeftVoltage, frontRightVoltage, rearLeftVoltage, rearRightVoltage);
+ frontLeft, frontRight, rearLeft, rearRight);
}
/** MecanumDriveMotorVoltages struct for serialization. */
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
index 0fd4b374169..ce19bc4137a 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry.java
@@ -23,14 +23,14 @@ public class MecanumDriveOdometry extends Odometry {
* @param kinematics The mecanum drive kinematics for your drivetrain.
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The distances driven by each wheel.
- * @param initialPoseMeters The starting position of the robot on the field.
+ * @param initialPose The starting position of the robot on the field.
*/
public MecanumDriveOdometry(
MecanumDriveKinematics kinematics,
Rotation2d gyroAngle,
MecanumDriveWheelPositions wheelPositions,
- Pose2d initialPoseMeters) {
- super(kinematics, gyroAngle, wheelPositions, initialPoseMeters);
+ Pose2d initialPose) {
+ super(kinematics, gyroAngle, wheelPositions, initialPose);
MathSharedStore.reportUsage(MathUsageId.kOdometry_MecanumDrive, 1);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java
index 00d66c0ab1b..b1691d3158c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java
@@ -32,14 +32,14 @@ public class MecanumDriveOdometry3d extends Odometry3d,
ProtobufSerializable,
StructSerializable {
- /** Distance measured by the front left wheel. */
- public double frontLeftMeters;
+ /** Distance measured by the front left wheel in meters. */
+ public double frontLeft;
- /** Distance measured by the front right wheel. */
- public double frontRightMeters;
+ /** Distance measured by the front right wheel in meters. */
+ public double frontRight;
- /** Distance measured by the rear left wheel. */
- public double rearLeftMeters;
+ /** Distance measured by the rear left wheel in meters. */
+ public double rearLeft;
- /** Distance measured by the rear right wheel. */
- public double rearRightMeters;
+ /** Distance measured by the rear right wheel in meters. */
+ public double rearRight;
/** MecanumDriveWheelPositions protobuf for serialization. */
public static final MecanumDriveWheelPositionsProto proto = new MecanumDriveWheelPositionsProto();
@@ -45,29 +45,26 @@ public MecanumDriveWheelPositions() {}
/**
* Constructs a MecanumDriveWheelPositions.
*
- * @param frontLeftMeters Distance measured by the front left wheel.
- * @param frontRightMeters Distance measured by the front right wheel.
- * @param rearLeftMeters Distance measured by the rear left wheel.
- * @param rearRightMeters Distance measured by the rear right wheel.
+ * @param frontLeft Distance measured by the front left wheel in meters.
+ * @param frontRight Distance measured by the front right wheel in meters.
+ * @param rearLeft Distance measured by the rear left wheel in meters.
+ * @param rearRight Distance measured by the rear right wheel in meters.
*/
public MecanumDriveWheelPositions(
- double frontLeftMeters,
- double frontRightMeters,
- double rearLeftMeters,
- double rearRightMeters) {
- this.frontLeftMeters = frontLeftMeters;
- this.frontRightMeters = frontRightMeters;
- this.rearLeftMeters = rearLeftMeters;
- this.rearRightMeters = rearRightMeters;
+ double frontLeft, double frontRight, double rearLeft, double rearRight) {
+ this.frontLeft = frontLeft;
+ this.frontRight = frontRight;
+ this.rearLeft = rearLeft;
+ this.rearRight = rearRight;
}
/**
* Constructs a MecanumDriveWheelPositions.
*
- * @param frontLeft Distance measured by the front left wheel.
- * @param frontRight Distance measured by the front right wheel.
- * @param rearLeft Distance measured by the rear left wheel.
- * @param rearRight Distance measured by the rear right wheel.
+ * @param frontLeft Distance measured by the front left wheel in meters.
+ * @param frontRight Distance measured by the front right wheel in meters.
+ * @param rearLeft Distance measured by the rear left wheel in meters.
+ * @param rearRight Distance measured by the rear right wheel in meters.
*/
public MecanumDriveWheelPositions(
Distance frontLeft, Distance frontRight, Distance rearLeft, Distance rearRight) {
@@ -77,15 +74,15 @@ public MecanumDriveWheelPositions(
@Override
public boolean equals(Object obj) {
return obj instanceof MecanumDriveWheelPositions other
- && Math.abs(other.frontLeftMeters - frontLeftMeters) < 1E-9
- && Math.abs(other.frontRightMeters - frontRightMeters) < 1E-9
- && Math.abs(other.rearLeftMeters - rearLeftMeters) < 1E-9
- && Math.abs(other.rearRightMeters - rearRightMeters) < 1E-9;
+ && Math.abs(other.frontLeft - frontLeft) < 1E-9
+ && Math.abs(other.frontRight - frontRight) < 1E-9
+ && Math.abs(other.rearLeft - rearLeft) < 1E-9
+ && Math.abs(other.rearRight - rearRight) < 1E-9;
}
@Override
public int hashCode() {
- return Objects.hash(frontLeftMeters, frontRightMeters, rearLeftMeters, rearRightMeters);
+ return Objects.hash(frontLeft, frontRight, rearLeft, rearRight);
}
@Override
@@ -93,15 +90,15 @@ public String toString() {
return String.format(
"MecanumDriveWheelPositions(Front Left: %.2f m, Front Right: %.2f m, "
+ "Rear Left: %.2f m, Rear Right: %.2f m)",
- frontLeftMeters, frontRightMeters, rearLeftMeters, rearRightMeters);
+ frontLeft, frontRight, rearLeft, rearRight);
}
@Override
public MecanumDriveWheelPositions interpolate(MecanumDriveWheelPositions endValue, double t) {
return new MecanumDriveWheelPositions(
- MathUtil.interpolate(this.frontLeftMeters, endValue.frontLeftMeters, t),
- MathUtil.interpolate(this.frontRightMeters, endValue.frontRightMeters, t),
- MathUtil.interpolate(this.rearLeftMeters, endValue.rearLeftMeters, t),
- MathUtil.interpolate(this.rearRightMeters, endValue.rearRightMeters, t));
+ MathUtil.interpolate(this.frontLeft, endValue.frontLeft, t),
+ MathUtil.interpolate(this.frontRight, endValue.frontRight, t),
+ MathUtil.interpolate(this.rearLeft, endValue.rearLeft, t),
+ MathUtil.interpolate(this.rearRight, endValue.rearRight, t));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
index 4240b9f5397..5c783990ec9 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveWheelSpeeds.java
@@ -14,17 +14,17 @@
/** Represents the wheel speeds for a mecanum drive drivetrain. */
public class MecanumDriveWheelSpeeds implements ProtobufSerializable, StructSerializable {
- /** Speed of the front left wheel. */
- public double frontLeftMetersPerSecond;
+ /** Speed of the front left wheel in meters per second. */
+ public double frontLeft;
- /** Speed of the front right wheel. */
- public double frontRightMetersPerSecond;
+ /** Speed of the front right wheel in meters per second. */
+ public double frontRight;
- /** Speed of the rear left wheel. */
- public double rearLeftMetersPerSecond;
+ /** Speed of the rear left wheel in meters per second. */
+ public double rearLeft;
- /** Speed of the rear right wheel. */
- public double rearRightMetersPerSecond;
+ /** Speed of the rear right wheel in meters per second. */
+ public double rearRight;
/** MecanumDriveWheelSpeeds protobuf for serialization. */
public static final MecanumDriveWheelSpeedsProto proto = new MecanumDriveWheelSpeedsProto();
@@ -38,29 +38,26 @@ public MecanumDriveWheelSpeeds() {}
/**
* Constructs a MecanumDriveWheelSpeeds.
*
- * @param frontLeftMetersPerSecond Speed of the front left wheel.
- * @param frontRightMetersPerSecond Speed of the front right wheel.
- * @param rearLeftMetersPerSecond Speed of the rear left wheel.
- * @param rearRightMetersPerSecond Speed of the rear right wheel.
+ * @param frontLeft Speed of the front left wheel in meters per second.
+ * @param frontRight Speed of the front right wheel in meters per second.
+ * @param rearLeft Speed of the rear left wheel in meters per second.
+ * @param rearRight Speed of the rear right wheel in meters per second.
*/
public MecanumDriveWheelSpeeds(
- double frontLeftMetersPerSecond,
- double frontRightMetersPerSecond,
- double rearLeftMetersPerSecond,
- double rearRightMetersPerSecond) {
- this.frontLeftMetersPerSecond = frontLeftMetersPerSecond;
- this.frontRightMetersPerSecond = frontRightMetersPerSecond;
- this.rearLeftMetersPerSecond = rearLeftMetersPerSecond;
- this.rearRightMetersPerSecond = rearRightMetersPerSecond;
+ double frontLeft, double frontRight, double rearLeft, double rearRight) {
+ this.frontLeft = frontLeft;
+ this.frontRight = frontRight;
+ this.rearLeft = rearLeft;
+ this.rearRight = rearRight;
}
/**
* Constructs a MecanumDriveWheelSpeeds.
*
- * @param frontLeft Speed of the front left wheel.
- * @param frontRight Speed of the front right wheel.
- * @param rearLeft Speed of the rear left wheel.
- * @param rearRight Speed of the rear right wheel.
+ * @param frontLeft Speed of the front left wheel in meters per second.
+ * @param frontRight Speed of the front right wheel in meters per second.
+ * @param rearLeft Speed of the rear left wheel in meters per second.
+ * @param rearRight Speed of the rear right wheel in meters per second.
*/
public MecanumDriveWheelSpeeds(
LinearVelocity frontLeft,
@@ -82,23 +79,18 @@ public MecanumDriveWheelSpeeds(
* reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
* absolute threshold, while maintaining the ratio of speeds between wheels.
*
- * @param attainableMaxSpeedMetersPerSecond The absolute max speed that a wheel can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a wheel can reach.
*/
- public void desaturate(double attainableMaxSpeedMetersPerSecond) {
- double realMaxSpeed =
- Math.max(Math.abs(frontLeftMetersPerSecond), Math.abs(frontRightMetersPerSecond));
- realMaxSpeed = Math.max(realMaxSpeed, Math.abs(rearLeftMetersPerSecond));
- realMaxSpeed = Math.max(realMaxSpeed, Math.abs(rearRightMetersPerSecond));
-
- if (realMaxSpeed > attainableMaxSpeedMetersPerSecond) {
- frontLeftMetersPerSecond =
- frontLeftMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
- frontRightMetersPerSecond =
- frontRightMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
- rearLeftMetersPerSecond =
- rearLeftMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
- rearRightMetersPerSecond =
- rearRightMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
+ public void desaturate(double attainableMaxSpeed) {
+ double realMaxSpeed = Math.max(Math.abs(frontLeft), Math.abs(frontRight));
+ realMaxSpeed = Math.max(realMaxSpeed, Math.abs(rearLeft));
+ realMaxSpeed = Math.max(realMaxSpeed, Math.abs(rearRight));
+
+ if (realMaxSpeed > attainableMaxSpeed) {
+ frontLeft = frontLeft / realMaxSpeed * attainableMaxSpeed;
+ frontRight = frontRight / realMaxSpeed * attainableMaxSpeed;
+ rearLeft = rearLeft / realMaxSpeed * attainableMaxSpeed;
+ rearRight = rearRight / realMaxSpeed * attainableMaxSpeed;
}
}
@@ -110,7 +102,7 @@ public void desaturate(double attainableMaxSpeedMetersPerSecond) {
* reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the
* absolute threshold, while maintaining the ratio of speeds between wheels.
*
- * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a wheel can reach.
*/
public void desaturate(LinearVelocity attainableMaxSpeed) {
desaturate(attainableMaxSpeed.in(MetersPerSecond));
@@ -127,10 +119,10 @@ public void desaturate(LinearVelocity attainableMaxSpeed) {
*/
public MecanumDriveWheelSpeeds plus(MecanumDriveWheelSpeeds other) {
return new MecanumDriveWheelSpeeds(
- frontLeftMetersPerSecond + other.frontLeftMetersPerSecond,
- frontRightMetersPerSecond + other.frontRightMetersPerSecond,
- rearLeftMetersPerSecond + other.rearLeftMetersPerSecond,
- rearRightMetersPerSecond + other.rearRightMetersPerSecond);
+ frontLeft + other.frontLeft,
+ frontRight + other.frontRight,
+ rearLeft + other.rearLeft,
+ rearRight + other.rearRight);
}
/**
@@ -145,10 +137,10 @@ public MecanumDriveWheelSpeeds plus(MecanumDriveWheelSpeeds other) {
*/
public MecanumDriveWheelSpeeds minus(MecanumDriveWheelSpeeds other) {
return new MecanumDriveWheelSpeeds(
- frontLeftMetersPerSecond - other.frontLeftMetersPerSecond,
- frontRightMetersPerSecond - other.frontRightMetersPerSecond,
- rearLeftMetersPerSecond - other.rearLeftMetersPerSecond,
- rearRightMetersPerSecond - other.rearRightMetersPerSecond);
+ frontLeft - other.frontLeft,
+ frontRight - other.frontRight,
+ rearLeft - other.rearLeft,
+ rearRight - other.rearRight);
}
/**
@@ -158,11 +150,7 @@ public MecanumDriveWheelSpeeds minus(MecanumDriveWheelSpeeds other) {
* @return The inverse of the current MecanumDriveWheelSpeeds.
*/
public MecanumDriveWheelSpeeds unaryMinus() {
- return new MecanumDriveWheelSpeeds(
- -frontLeftMetersPerSecond,
- -frontRightMetersPerSecond,
- -rearLeftMetersPerSecond,
- -rearRightMetersPerSecond);
+ return new MecanumDriveWheelSpeeds(-frontLeft, -frontRight, -rearLeft, -rearRight);
}
/**
@@ -176,10 +164,7 @@ public MecanumDriveWheelSpeeds unaryMinus() {
*/
public MecanumDriveWheelSpeeds times(double scalar) {
return new MecanumDriveWheelSpeeds(
- frontLeftMetersPerSecond * scalar,
- frontRightMetersPerSecond * scalar,
- rearLeftMetersPerSecond * scalar,
- rearRightMetersPerSecond * scalar);
+ frontLeft * scalar, frontRight * scalar, rearLeft * scalar, rearRight * scalar);
}
/**
@@ -193,10 +178,7 @@ public MecanumDriveWheelSpeeds times(double scalar) {
*/
public MecanumDriveWheelSpeeds div(double scalar) {
return new MecanumDriveWheelSpeeds(
- frontLeftMetersPerSecond / scalar,
- frontRightMetersPerSecond / scalar,
- rearLeftMetersPerSecond / scalar,
- rearRightMetersPerSecond / scalar);
+ frontLeft / scalar, frontRight / scalar, rearLeft / scalar, rearRight / scalar);
}
@Override
@@ -204,9 +186,6 @@ public String toString() {
return String.format(
"MecanumDriveWheelSpeeds(Front Left: %.2f m/s, Front Right: %.2f m/s, "
+ "Rear Left: %.2f m/s, Rear Right: %.2f m/s)",
- frontLeftMetersPerSecond,
- frontRightMetersPerSecond,
- rearLeftMetersPerSecond,
- rearRightMetersPerSecond);
+ frontLeft, frontRight, rearLeft, rearRight);
}
}
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 6a09f92bffd..9c99696590a 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
@@ -21,7 +21,7 @@
*/
public class Odometry {
private final Kinematics, T> m_kinematics;
- private Pose2d m_poseMeters;
+ private Pose2d m_pose;
private Rotation2d m_gyroOffset;
private Rotation2d m_previousAngle;
@@ -33,17 +33,14 @@ public class Odometry {
* @param kinematics The kinematics of the drivebase.
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param initialPoseMeters The starting position of the robot on the field.
+ * @param initialPose The starting position of the robot on the field.
*/
public Odometry(
- Kinematics, T> kinematics,
- Rotation2d gyroAngle,
- T wheelPositions,
- Pose2d initialPoseMeters) {
+ Kinematics, T> kinematics, Rotation2d gyroAngle, T wheelPositions, Pose2d initialPose) {
m_kinematics = kinematics;
- m_poseMeters = initialPoseMeters;
- m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
- m_previousAngle = m_poseMeters.getRotation();
+ m_pose = initialPose;
+ m_gyroOffset = m_pose.getRotation().minus(gyroAngle);
+ m_previousAngle = m_pose.getRotation();
m_previousWheelPositions = m_kinematics.copy(wheelPositions);
}
@@ -55,24 +52,24 @@ public Odometry(
*
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param poseMeters The position on the field that your robot is at.
+ * @param pose The position on the field that your robot is at.
*/
- public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters) {
- m_poseMeters = poseMeters;
- m_previousAngle = m_poseMeters.getRotation();
- m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
+ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d pose) {
+ m_pose = pose;
+ m_previousAngle = m_pose.getRotation();
+ m_gyroOffset = m_pose.getRotation().minus(gyroAngle);
m_kinematics.copyInto(wheelPositions, m_previousWheelPositions);
}
/**
* Resets the pose.
*
- * @param poseMeters The pose to reset to.
+ * @param pose The pose to reset to.
*/
- public void resetPose(Pose2d poseMeters) {
- m_gyroOffset = m_gyroOffset.plus(poseMeters.getRotation().minus(m_poseMeters.getRotation()));
- m_poseMeters = poseMeters;
- m_previousAngle = m_poseMeters.getRotation();
+ public void resetPose(Pose2d pose) {
+ m_gyroOffset = m_gyroOffset.plus(pose.getRotation().minus(m_pose.getRotation()));
+ m_pose = pose;
+ m_previousAngle = m_pose.getRotation();
}
/**
@@ -81,7 +78,7 @@ public void resetPose(Pose2d poseMeters) {
* @param translation The translation to reset to.
*/
public void resetTranslation(Translation2d translation) {
- m_poseMeters = new Pose2d(translation, m_poseMeters.getRotation());
+ m_pose = new Pose2d(translation, m_pose.getRotation());
}
/**
@@ -90,9 +87,9 @@ public void resetTranslation(Translation2d translation) {
* @param rotation The rotation to reset to.
*/
public void resetRotation(Rotation2d rotation) {
- m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_poseMeters.getRotation()));
- m_poseMeters = new Pose2d(m_poseMeters.getTranslation(), rotation);
- m_previousAngle = m_poseMeters.getRotation();
+ m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_pose.getRotation()));
+ m_pose = new Pose2d(m_pose.getTranslation(), rotation);
+ m_previousAngle = m_pose.getRotation();
}
/**
@@ -100,8 +97,8 @@ public void resetRotation(Rotation2d rotation) {
*
* @return The pose of the robot (x and y are in meters).
*/
- public Pose2d getPoseMeters() {
- return m_poseMeters;
+ public Pose2d getPose() {
+ return m_pose;
}
/**
@@ -120,12 +117,12 @@ public Pose2d update(Rotation2d gyroAngle, T wheelPositions) {
var twist = m_kinematics.toTwist2d(m_previousWheelPositions, wheelPositions);
twist.dtheta = angle.minus(m_previousAngle).getRadians();
- var newPose = m_poseMeters.exp(twist);
+ var newPose = m_pose.exp(twist);
m_kinematics.copyInto(wheelPositions, m_previousWheelPositions);
m_previousAngle = angle;
- m_poseMeters = new Pose2d(newPose.getTranslation(), angle);
+ m_pose = new Pose2d(newPose.getTranslation(), angle);
- return m_poseMeters;
+ return m_pose;
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java
index c1ccd3c9a16..e5314d7a29c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java
@@ -30,7 +30,7 @@
*/
public class Odometry3d {
private final Kinematics, T> m_kinematics;
- private Pose3d m_poseMeters;
+ private Pose3d m_pose;
private Rotation3d m_gyroOffset;
private Rotation3d m_previousAngle;
@@ -42,17 +42,14 @@ public class Odometry3d {
* @param kinematics The kinematics of the drivebase.
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param initialPoseMeters The starting position of the robot on the field.
+ * @param initialPose The starting position of the robot on the field.
*/
public Odometry3d(
- Kinematics, T> kinematics,
- Rotation3d gyroAngle,
- T wheelPositions,
- Pose3d initialPoseMeters) {
+ Kinematics, T> kinematics, Rotation3d gyroAngle, T wheelPositions, Pose3d initialPose) {
m_kinematics = kinematics;
- m_poseMeters = initialPoseMeters;
- m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
- m_previousAngle = m_poseMeters.getRotation();
+ m_pose = initialPose;
+ m_gyroOffset = m_pose.getRotation().minus(gyroAngle);
+ m_previousAngle = m_pose.getRotation();
m_previousWheelPositions = m_kinematics.copy(wheelPositions);
}
@@ -64,24 +61,24 @@ public Odometry3d(
*
* @param gyroAngle The angle reported by the gyroscope.
* @param wheelPositions The current encoder readings.
- * @param poseMeters The position on the field that your robot is at.
+ * @param pose The position on the field that your robot is at.
*/
- public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d poseMeters) {
- m_poseMeters = poseMeters;
- m_previousAngle = m_poseMeters.getRotation();
- m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle);
+ public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d pose) {
+ m_pose = pose;
+ m_previousAngle = m_pose.getRotation();
+ m_gyroOffset = m_pose.getRotation().minus(gyroAngle);
m_kinematics.copyInto(wheelPositions, m_previousWheelPositions);
}
/**
* Resets the pose.
*
- * @param poseMeters The pose to reset to.
+ * @param pose The pose to reset to.
*/
- public void resetPose(Pose3d poseMeters) {
- m_gyroOffset = m_gyroOffset.plus(poseMeters.getRotation().minus(m_poseMeters.getRotation()));
- m_poseMeters = poseMeters;
- m_previousAngle = m_poseMeters.getRotation();
+ public void resetPose(Pose3d pose) {
+ m_gyroOffset = m_gyroOffset.plus(pose.getRotation().minus(m_pose.getRotation()));
+ m_pose = pose;
+ m_previousAngle = m_pose.getRotation();
}
/**
@@ -90,7 +87,7 @@ public void resetPose(Pose3d poseMeters) {
* @param translation The translation to reset to.
*/
public void resetTranslation(Translation3d translation) {
- m_poseMeters = new Pose3d(translation, m_poseMeters.getRotation());
+ m_pose = new Pose3d(translation, m_pose.getRotation());
}
/**
@@ -99,9 +96,9 @@ public void resetTranslation(Translation3d translation) {
* @param rotation The rotation to reset to.
*/
public void resetRotation(Rotation3d rotation) {
- m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_poseMeters.getRotation()));
- m_poseMeters = new Pose3d(m_poseMeters.getTranslation(), rotation);
- m_previousAngle = m_poseMeters.getRotation();
+ m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_pose.getRotation()));
+ m_pose = new Pose3d(m_pose.getTranslation(), rotation);
+ m_previousAngle = m_pose.getRotation();
}
/**
@@ -109,8 +106,8 @@ public void resetRotation(Rotation3d rotation) {
*
* @return The pose of the robot (x, y, and z are in meters).
*/
- public Pose3d getPoseMeters() {
- return m_poseMeters;
+ public Pose3d getPose() {
+ return m_pose;
}
/**
@@ -137,12 +134,12 @@ public Pose3d update(Rotation3d gyroAngle, T wheelPositions) {
angle_difference.get(1),
angle_difference.get(2));
- var newPose = m_poseMeters.exp(twist);
+ var newPose = m_pose.exp(twist);
m_kinematics.copyInto(wheelPositions, m_previousWheelPositions);
m_previousAngle = angle;
- m_poseMeters = new Pose3d(newPose.getTranslation(), angle);
+ m_pose = new Pose3d(newPose.getTranslation(), angle);
- return m_poseMeters;
+ return m_pose;
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
index 45c3f3bb235..0f783ea15a0 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveKinematics.java
@@ -62,15 +62,15 @@ public class SwerveDriveKinematics
* also expected that you pass in the module states in the same order when calling the forward
* kinematics methods.
*
- * @param moduleTranslationsMeters The locations of the modules relative to the physical center of
- * the robot.
+ * @param moduleTranslations The locations of the modules relative to the physical center of the
+ * robot.
*/
- public SwerveDriveKinematics(Translation2d... moduleTranslationsMeters) {
- if (moduleTranslationsMeters.length < 2) {
+ public SwerveDriveKinematics(Translation2d... moduleTranslations) {
+ if (moduleTranslations.length < 2) {
throw new IllegalArgumentException("A swerve drive requires at least two modules");
}
- m_numModules = moduleTranslationsMeters.length;
- m_modules = Arrays.copyOf(moduleTranslationsMeters, m_numModules);
+ m_numModules = moduleTranslations.length;
+ m_modules = Arrays.copyOf(moduleTranslations, m_numModules);
m_moduleHeadings = new Rotation2d[m_numModules];
Arrays.fill(m_moduleHeadings, Rotation2d.kZero);
m_inverseKinematics = new SimpleMatrix(m_numModules * 2, 3);
@@ -112,21 +112,19 @@ public void resetHeadings(Rotation2d... moduleHeadings) {
* the previously calculated module angle will be maintained.
*
* @param chassisSpeeds The desired chassis speed.
- * @param centerOfRotationMeters The center of rotation. For example, if you set the center of
- * rotation at one corner of the robot and provide a chassis speed that only has a dtheta
- * component, the robot will rotate around that corner.
+ * @param centerOfRotation The center of rotation. For example, if you set the center of rotation
+ * at one corner of the robot and provide a chassis speed that only has a dtheta component,
+ * the robot will rotate around that corner.
* @return An array containing the module states. Use caution because these module states are not
* normalized. Sometimes, a user input may cause one of the module speeds to go above the
* attainable max velocity. Use the {@link #desaturateWheelSpeeds(SwerveModuleState[], double)
* DesaturateWheelSpeeds} function to rectify this issue.
*/
public SwerveModuleState[] toSwerveModuleStates(
- ChassisSpeeds chassisSpeeds, Translation2d centerOfRotationMeters) {
+ ChassisSpeeds chassisSpeeds, Translation2d centerOfRotation) {
var moduleStates = new SwerveModuleState[m_numModules];
- if (chassisSpeeds.vxMetersPerSecond == 0.0
- && chassisSpeeds.vyMetersPerSecond == 0.0
- && chassisSpeeds.omegaRadiansPerSecond == 0.0) {
+ if (chassisSpeeds.vx == 0.0 && chassisSpeeds.vy == 0.0 && chassisSpeeds.omega == 0.0) {
for (int i = 0; i < m_numModules; i++) {
moduleStates[i] = new SwerveModuleState(0.0, m_moduleHeadings[i]);
}
@@ -134,31 +132,18 @@ public SwerveModuleState[] toSwerveModuleStates(
return moduleStates;
}
- if (!centerOfRotationMeters.equals(m_prevCoR)) {
+ if (!centerOfRotation.equals(m_prevCoR)) {
for (int i = 0; i < m_numModules; i++) {
m_inverseKinematics.setRow(
- i * 2 + 0,
- 0, /* Start Data */
- 1,
- 0,
- -m_modules[i].getY() + centerOfRotationMeters.getY());
+ i * 2 + 0, 0, /* Start Data */ 1, 0, -m_modules[i].getY() + centerOfRotation.getY());
m_inverseKinematics.setRow(
- i * 2 + 1,
- 0, /* Start Data */
- 0,
- 1,
- +m_modules[i].getX() - centerOfRotationMeters.getX());
+ i * 2 + 1, 0, /* Start Data */ 0, 1, +m_modules[i].getX() - centerOfRotation.getX());
}
- m_prevCoR = centerOfRotationMeters;
+ m_prevCoR = centerOfRotation;
}
var chassisSpeedsVector = new SimpleMatrix(3, 1);
- chassisSpeedsVector.setColumn(
- 0,
- 0,
- chassisSpeeds.vxMetersPerSecond,
- chassisSpeeds.vyMetersPerSecond,
- chassisSpeeds.omegaRadiansPerSecond);
+ chassisSpeedsVector.setColumn(0, 0, chassisSpeeds.vx, chassisSpeeds.vy, chassisSpeeds.omega);
var moduleStatesMatrix = m_inverseKinematics.mult(chassisSpeedsVector);
@@ -213,8 +198,8 @@ public ChassisSpeeds toChassisSpeeds(SwerveModuleState... moduleStates) {
for (int i = 0; i < m_numModules; i++) {
var module = moduleStates[i];
- moduleStatesMatrix.set(i * 2, 0, module.speedMetersPerSecond * module.angle.getCos());
- moduleStatesMatrix.set(i * 2 + 1, module.speedMetersPerSecond * module.angle.getSin());
+ moduleStatesMatrix.set(i * 2, 0, module.speed * module.angle.getCos());
+ moduleStatesMatrix.set(i * 2 + 1, module.speed * module.angle.getSin());
}
var chassisSpeedsVector = m_forwardKinematics.mult(moduleStatesMatrix);
@@ -244,8 +229,8 @@ public Twist2d toTwist2d(SwerveModulePosition... moduleDeltas) {
for (int i = 0; i < m_numModules; i++) {
var module = moduleDeltas[i];
- moduleDeltaMatrix.set(i * 2, 0, module.distanceMeters * module.angle.getCos());
- moduleDeltaMatrix.set(i * 2 + 1, module.distanceMeters * module.angle.getSin());
+ moduleDeltaMatrix.set(i * 2, 0, module.distance * module.angle.getCos());
+ moduleDeltaMatrix.set(i * 2 + 1, module.distance * module.angle.getSin());
}
var chassisDeltaVector = m_forwardKinematics.mult(moduleDeltaMatrix);
@@ -260,8 +245,7 @@ public Twist2d toTwist2d(SwerveModulePosition[] start, SwerveModulePosition[] en
}
var newPositions = new SwerveModulePosition[start.length];
for (int i = 0; i < start.length; i++) {
- newPositions[i] =
- new SwerveModulePosition(end[i].distanceMeters - start[i].distanceMeters, end[i].angle);
+ newPositions[i] = new SwerveModulePosition(end[i].distance - start[i].distance, end[i].angle);
}
return toTwist2d(newPositions);
}
@@ -276,18 +260,17 @@ public Twist2d toTwist2d(SwerveModulePosition[] start, SwerveModulePosition[] en
*
* @param moduleStates Reference to array of module states. The array will be mutated with the
* normalized speeds!
- * @param attainableMaxSpeedMetersPerSecond The absolute max speed that a module can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a module can reach.
*/
public static void desaturateWheelSpeeds(
- SwerveModuleState[] moduleStates, double attainableMaxSpeedMetersPerSecond) {
+ SwerveModuleState[] moduleStates, double attainableMaxSpeed) {
double realMaxSpeed = 0;
for (SwerveModuleState moduleState : moduleStates) {
- realMaxSpeed = Math.max(realMaxSpeed, Math.abs(moduleState.speedMetersPerSecond));
+ realMaxSpeed = Math.max(realMaxSpeed, Math.abs(moduleState.speed));
}
- if (realMaxSpeed > attainableMaxSpeedMetersPerSecond) {
+ if (realMaxSpeed > attainableMaxSpeed) {
for (SwerveModuleState moduleState : moduleStates) {
- moduleState.speedMetersPerSecond =
- moduleState.speedMetersPerSecond / realMaxSpeed * attainableMaxSpeedMetersPerSecond;
+ moduleState.speed = moduleState.speed / realMaxSpeed * attainableMaxSpeed;
}
}
}
@@ -302,7 +285,7 @@ public static void desaturateWheelSpeeds(
*
* @param moduleStates Reference to array of module states. The array will be mutated with the
* normalized speeds!
- * @param attainableMaxSpeed The absolute max speed that a module can reach.
+ * @param attainableMaxSpeed The absolute max speed in meters per second that a module can reach.
*/
public static void desaturateWheelSpeeds(
SwerveModuleState[] moduleStates, LinearVelocity attainableMaxSpeed) {
@@ -321,38 +304,37 @@ public static void desaturateWheelSpeeds(
* @param moduleStates Reference to array of module states. The array will be mutated with the
* normalized speeds!
* @param desiredChassisSpeed The desired speed of the robot
- * @param attainableMaxModuleSpeedMetersPerSecond The absolute max speed that a module can reach
- * @param attainableMaxTranslationalSpeedMetersPerSecond The absolute max speed that your robot
- * can reach while translating
- * @param attainableMaxRotationalVelocityRadiansPerSecond The absolute max speed the robot can
- * reach while rotating
+ * @param attainableMaxModuleSpeed The absolute max speed in meters per second that a module can
+ * reach
+ * @param attainableMaxTranslationalSpeed The absolute max speed in meters per second that your
+ * robot can reach while translating
+ * @param attainableMaxRotationalVelocity The absolute max speed in radians per second the robot
+ * can reach while rotating
*/
public static void desaturateWheelSpeeds(
SwerveModuleState[] moduleStates,
ChassisSpeeds desiredChassisSpeed,
- double attainableMaxModuleSpeedMetersPerSecond,
- double attainableMaxTranslationalSpeedMetersPerSecond,
- double attainableMaxRotationalVelocityRadiansPerSecond) {
+ double attainableMaxModuleSpeed,
+ double attainableMaxTranslationalSpeed,
+ double attainableMaxRotationalVelocity) {
double realMaxSpeed = 0;
for (SwerveModuleState moduleState : moduleStates) {
- realMaxSpeed = Math.max(realMaxSpeed, Math.abs(moduleState.speedMetersPerSecond));
+ realMaxSpeed = Math.max(realMaxSpeed, Math.abs(moduleState.speed));
}
- if (attainableMaxTranslationalSpeedMetersPerSecond == 0
- || attainableMaxRotationalVelocityRadiansPerSecond == 0
+ if (attainableMaxTranslationalSpeed == 0
+ || attainableMaxRotationalVelocity == 0
|| realMaxSpeed == 0) {
return;
}
double translationalK =
- Math.hypot(desiredChassisSpeed.vxMetersPerSecond, desiredChassisSpeed.vyMetersPerSecond)
- / attainableMaxTranslationalSpeedMetersPerSecond;
- double rotationalK =
- Math.abs(desiredChassisSpeed.omegaRadiansPerSecond)
- / attainableMaxRotationalVelocityRadiansPerSecond;
+ Math.hypot(desiredChassisSpeed.vx, desiredChassisSpeed.vy)
+ / attainableMaxTranslationalSpeed;
+ double rotationalK = Math.abs(desiredChassisSpeed.omega) / attainableMaxRotationalVelocity;
double k = Math.max(translationalK, rotationalK);
- double scale = Math.min(k * attainableMaxModuleSpeedMetersPerSecond / realMaxSpeed, 1);
+ double scale = Math.min(k * attainableMaxModuleSpeed / realMaxSpeed, 1);
for (SwerveModuleState moduleState : moduleStates) {
- moduleState.speedMetersPerSecond *= scale;
+ moduleState.speed *= scale;
}
}
@@ -403,7 +385,7 @@ public void copyInto(SwerveModulePosition[] positions, SwerveModulePosition[] ou
throw new IllegalArgumentException("Inconsistent number of modules!");
}
for (int i = 0; i < positions.length; ++i) {
- output[i].distanceMeters = positions[i].distanceMeters;
+ output[i].distance = positions[i].distance;
output[i].angle = positions[i].angle;
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java
index a081a702498..fc65e5f788f 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModulePosition.java
@@ -22,8 +22,8 @@ public class SwerveModulePosition
Interpolatable,
ProtobufSerializable,
StructSerializable {
- /** Distance measured by the wheel of the module. */
- public double distanceMeters;
+ /** Distance measured by the wheel of the module in meters. */
+ public double distance;
/** Angle of the module. */
public Rotation2d angle = Rotation2d.kZero;
@@ -40,11 +40,11 @@ public SwerveModulePosition() {}
/**
* Constructs a SwerveModulePosition.
*
- * @param distanceMeters The distance measured by the wheel of the module.
+ * @param distance The distance measured by the wheel of the module in meters.
* @param angle The angle of the module.
*/
- public SwerveModulePosition(double distanceMeters, Rotation2d angle) {
- this.distanceMeters = distanceMeters;
+ public SwerveModulePosition(double distance, Rotation2d angle) {
+ this.distance = distance;
this.angle = angle;
}
@@ -61,13 +61,13 @@ public SwerveModulePosition(Distance distance, Rotation2d angle) {
@Override
public boolean equals(Object obj) {
return obj instanceof SwerveModulePosition other
- && Math.abs(other.distanceMeters - distanceMeters) < 1E-9
+ && Math.abs(other.distance - distance) < 1E-9
&& angle.equals(other.angle);
}
@Override
public int hashCode() {
- return Objects.hash(distanceMeters, angle);
+ return Objects.hash(distance, angle);
}
/**
@@ -79,13 +79,12 @@ public int hashCode() {
*/
@Override
public int compareTo(SwerveModulePosition other) {
- return Double.compare(this.distanceMeters, other.distanceMeters);
+ return Double.compare(this.distance, other.distance);
}
@Override
public String toString() {
- return String.format(
- "SwerveModulePosition(Distance: %.2f m, Angle: %s)", distanceMeters, angle);
+ return String.format("SwerveModulePosition(Distance: %.2f m, Angle: %s)", distance, angle);
}
/**
@@ -94,13 +93,13 @@ public String toString() {
* @return A copy.
*/
public SwerveModulePosition copy() {
- return new SwerveModulePosition(distanceMeters, angle);
+ return new SwerveModulePosition(distance, angle);
}
@Override
public SwerveModulePosition interpolate(SwerveModulePosition endValue, double t) {
return new SwerveModulePosition(
- MathUtil.interpolate(this.distanceMeters, endValue.distanceMeters, t),
+ MathUtil.interpolate(this.distance, endValue.distance, t),
this.angle.interpolate(endValue.angle, t));
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
index 6cadd35b4a8..8855f980bea 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java
@@ -17,8 +17,8 @@
/** Represents the state of one swerve module. */
public class SwerveModuleState
implements Comparable, ProtobufSerializable, StructSerializable {
- /** Speed of the wheel of the module. */
- public double speedMetersPerSecond;
+ /** Speed of the wheel of the module in meters per second. */
+ public double speed;
/** Angle of the module. */
public Rotation2d angle = Rotation2d.kZero;
@@ -35,11 +35,11 @@ public SwerveModuleState() {}
/**
* Constructs a SwerveModuleState.
*
- * @param speedMetersPerSecond The speed of the wheel of the module.
+ * @param speed The speed of the wheel of the module in meters per second.
* @param angle The angle of the module.
*/
- public SwerveModuleState(double speedMetersPerSecond, Rotation2d angle) {
- this.speedMetersPerSecond = speedMetersPerSecond;
+ public SwerveModuleState(double speed, Rotation2d angle) {
+ this.speed = speed;
this.angle = angle;
}
@@ -56,13 +56,13 @@ public SwerveModuleState(LinearVelocity speed, Rotation2d angle) {
@Override
public boolean equals(Object obj) {
return obj instanceof SwerveModuleState other
- && Math.abs(other.speedMetersPerSecond - speedMetersPerSecond) < 1E-9
+ && Math.abs(other.speed - speed) < 1E-9
&& angle.equals(other.angle);
}
@Override
public int hashCode() {
- return Objects.hash(speedMetersPerSecond, angle);
+ return Objects.hash(speed, angle);
}
/**
@@ -74,13 +74,12 @@ public int hashCode() {
*/
@Override
public int compareTo(SwerveModuleState other) {
- return Double.compare(this.speedMetersPerSecond, other.speedMetersPerSecond);
+ return Double.compare(this.speed, other.speed);
}
@Override
public String toString() {
- return String.format(
- "SwerveModuleState(Speed: %.2f m/s, Angle: %s)", speedMetersPerSecond, angle);
+ return String.format("SwerveModuleState(Speed: %.2f m/s, Angle: %s)", speed, angle);
}
/**
@@ -93,7 +92,7 @@ public String toString() {
public void optimize(Rotation2d currentAngle) {
var delta = angle.minus(currentAngle);
if (Math.abs(delta.getDegrees()) > 90.0) {
- speedMetersPerSecond *= -1;
+ speed *= -1;
angle = angle.rotateBy(Rotation2d.kPi);
}
}
@@ -114,9 +113,9 @@ public static SwerveModuleState optimize(
var delta = desiredState.angle.minus(currentAngle);
if (Math.abs(delta.getDegrees()) > 90.0) {
return new SwerveModuleState(
- -desiredState.speedMetersPerSecond, desiredState.angle.rotateBy(Rotation2d.kPi));
+ -desiredState.speed, desiredState.angle.rotateBy(Rotation2d.kPi));
} else {
- return new SwerveModuleState(desiredState.speedMetersPerSecond, desiredState.angle);
+ return new SwerveModuleState(desiredState.speed, desiredState.angle);
}
}
@@ -128,6 +127,6 @@ public static SwerveModuleState optimize(
* @param currentAngle The current module angle.
*/
public void cosineScale(Rotation2d currentAngle) {
- speedMetersPerSecond *= angle.minus(currentAngle).getCos();
+ speed *= angle.minus(currentAngle).getCos();
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/ChassisSpeedsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/ChassisSpeedsProto.java
index b20d23bbc9f..8a83b416782 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/ChassisSpeedsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/ChassisSpeedsProto.java
@@ -32,8 +32,8 @@ public ChassisSpeeds unpack(ProtobufChassisSpeeds msg) {
@Override
public void pack(ProtobufChassisSpeeds msg, ChassisSpeeds value) {
- msg.setVx(value.vxMetersPerSecond);
- msg.setVy(value.vyMetersPerSecond);
- msg.setOmega(value.omegaRadiansPerSecond);
+ msg.setVx(value.vx);
+ msg.setVy(value.vy);
+ msg.setOmega(value.omega);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveKinematicsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveKinematicsProto.java
index d1a8969d162..311b4d80576 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveKinematicsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveKinematicsProto.java
@@ -28,11 +28,11 @@ public ProtobufDifferentialDriveKinematics createMessage() {
@Override
public DifferentialDriveKinematics unpack(ProtobufDifferentialDriveKinematics msg) {
- return new DifferentialDriveKinematics(msg.getTrackWidth());
+ return new DifferentialDriveKinematics(msg.getTrackwidth());
}
@Override
public void pack(ProtobufDifferentialDriveKinematics msg, DifferentialDriveKinematics value) {
- msg.setTrackWidth(value.trackWidthMeters);
+ msg.setTrackwidth(value.trackwidth);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelPositionsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelPositionsProto.java
index 982756b5b7c..23a70393831 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelPositionsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelPositionsProto.java
@@ -34,7 +34,7 @@ public DifferentialDriveWheelPositions unpack(ProtobufDifferentialDriveWheelPosi
@Override
public void pack(
ProtobufDifferentialDriveWheelPositions msg, DifferentialDriveWheelPositions value) {
- msg.setLeft(value.leftMeters);
- msg.setRight(value.rightMeters);
+ msg.setLeft(value.left);
+ msg.setRight(value.right);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.java
index e30df565749..c6023ac761c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.java
@@ -33,7 +33,7 @@ public DifferentialDriveWheelSpeeds unpack(ProtobufDifferentialDriveWheelSpeeds
@Override
public void pack(ProtobufDifferentialDriveWheelSpeeds msg, DifferentialDriveWheelSpeeds value) {
- msg.setLeft(value.leftMetersPerSecond);
- msg.setRight(value.rightMetersPerSecond);
+ msg.setLeft(value.left);
+ msg.setRight(value.right);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
index 0b5f0c2583b..ae30ee84e7f 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveMotorVoltagesProto.java
@@ -34,9 +34,9 @@ public MecanumDriveMotorVoltages unpack(ProtobufMecanumDriveMotorVoltages msg) {
@Override
public void pack(ProtobufMecanumDriveMotorVoltages msg, MecanumDriveMotorVoltages value) {
- msg.setFrontLeft(value.frontLeftVoltage);
- msg.setFrontRight(value.frontRightVoltage);
- msg.setRearLeft(value.rearLeftVoltage);
- msg.setRearRight(value.rearRightVoltage);
+ msg.setFrontLeft(value.frontLeft);
+ msg.setFrontRight(value.frontRight);
+ msg.setRearLeft(value.rearLeft);
+ msg.setRearRight(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelPositionsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelPositionsProto.java
index d4f0f5a3ce4..6469657f9de 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelPositionsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelPositionsProto.java
@@ -34,9 +34,9 @@ public MecanumDriveWheelPositions unpack(ProtobufMecanumDriveWheelPositions msg)
@Override
public void pack(ProtobufMecanumDriveWheelPositions msg, MecanumDriveWheelPositions value) {
- msg.setFrontLeft(value.frontLeftMeters);
- msg.setFrontRight(value.frontRightMeters);
- msg.setRearLeft(value.rearLeftMeters);
- msg.setRearRight(value.rearRightMeters);
+ msg.setFrontLeft(value.frontLeft);
+ msg.setFrontRight(value.frontRight);
+ msg.setRearLeft(value.rearLeft);
+ msg.setRearRight(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelSpeedsProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelSpeedsProto.java
index 85e8fd10a35..dffa38bcc78 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelSpeedsProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/MecanumDriveWheelSpeedsProto.java
@@ -34,9 +34,9 @@ public MecanumDriveWheelSpeeds unpack(ProtobufMecanumDriveWheelSpeeds msg) {
@Override
public void pack(ProtobufMecanumDriveWheelSpeeds msg, MecanumDriveWheelSpeeds value) {
- msg.setFrontLeft(value.frontLeftMetersPerSecond);
- msg.setFrontRight(value.frontRightMetersPerSecond);
- msg.setRearLeft(value.rearLeftMetersPerSecond);
- msg.setRearRight(value.rearRightMetersPerSecond);
+ msg.setFrontLeft(value.frontLeft);
+ msg.setFrontRight(value.frontRight);
+ msg.setRearLeft(value.rearLeft);
+ msg.setRearRight(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModulePositionProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModulePositionProto.java
index 97cadf28c3a..a445c7b05f5 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModulePositionProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModulePositionProto.java
@@ -34,7 +34,7 @@ public SwerveModulePosition unpack(ProtobufSwerveModulePosition msg) {
@Override
public void pack(ProtobufSwerveModulePosition msg, SwerveModulePosition value) {
- msg.setDistance(value.distanceMeters);
+ msg.setDistance(value.distance);
Rotation2d.proto.pack(msg.getMutableAngle(), value.angle);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModuleStateProto.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModuleStateProto.java
index cccff4d5910..f8de1375204 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModuleStateProto.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/proto/SwerveModuleStateProto.java
@@ -34,7 +34,7 @@ public SwerveModuleState unpack(ProtobufSwerveModuleState msg) {
@Override
public void pack(ProtobufSwerveModuleState msg, SwerveModuleState value) {
- msg.setSpeed(value.speedMetersPerSecond);
+ msg.setSpeed(value.speed);
Rotation2d.proto.pack(msg.getMutableAngle(), value.angle);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/ChassisSpeedsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/ChassisSpeedsStruct.java
index 16457f5e096..14d2030389d 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/ChassisSpeedsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/ChassisSpeedsStruct.java
@@ -39,8 +39,8 @@ public ChassisSpeeds unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, ChassisSpeeds value) {
- bb.putDouble(value.vxMetersPerSecond);
- bb.putDouble(value.vyMetersPerSecond);
- bb.putDouble(value.omegaRadiansPerSecond);
+ bb.putDouble(value.vx);
+ bb.putDouble(value.vy);
+ bb.putDouble(value.omega);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveKinematicsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveKinematicsStruct.java
index cc696ec908c..621af5741a7 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveKinematicsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveKinematicsStruct.java
@@ -26,17 +26,17 @@ public int getSize() {
@Override
public String getSchema() {
- return "double track_width";
+ return "double trackwidth";
}
@Override
public DifferentialDriveKinematics unpack(ByteBuffer bb) {
- double trackWidth = bb.getDouble();
- return new DifferentialDriveKinematics(trackWidth);
+ double trackwidth = bb.getDouble();
+ return new DifferentialDriveKinematics(trackwidth);
}
@Override
public void pack(ByteBuffer bb, DifferentialDriveKinematics value) {
- bb.putDouble(value.trackWidthMeters);
+ bb.putDouble(value.trackwidth);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.java
index e8d86d1733e..8b2aeaf0bbc 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.java
@@ -39,7 +39,7 @@ public DifferentialDriveWheelPositions unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, DifferentialDriveWheelPositions value) {
- bb.putDouble(value.leftMeters);
- bb.putDouble(value.rightMeters);
+ bb.putDouble(value.left);
+ bb.putDouble(value.right);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.java
index 1d5819737b5..dca590766d2 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.java
@@ -38,7 +38,7 @@ public DifferentialDriveWheelSpeeds unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, DifferentialDriveWheelSpeeds value) {
- bb.putDouble(value.leftMetersPerSecond);
- bb.putDouble(value.rightMetersPerSecond);
+ bb.putDouble(value.left);
+ bb.putDouble(value.right);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
index 8078e0a7b16..2567d5fec28 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveMotorVoltagesStruct.java
@@ -40,9 +40,9 @@ public MecanumDriveMotorVoltages unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, MecanumDriveMotorVoltages value) {
- bb.putDouble(value.frontLeftVoltage);
- bb.putDouble(value.frontRightVoltage);
- bb.putDouble(value.rearLeftVoltage);
- bb.putDouble(value.rearRightVoltage);
+ bb.putDouble(value.frontLeft);
+ bb.putDouble(value.frontRight);
+ bb.putDouble(value.rearLeft);
+ bb.putDouble(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelPositionsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelPositionsStruct.java
index 5b8d7bf2199..5974282996b 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelPositionsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelPositionsStruct.java
@@ -40,9 +40,9 @@ public MecanumDriveWheelPositions unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, MecanumDriveWheelPositions value) {
- bb.putDouble(value.frontLeftMeters);
- bb.putDouble(value.frontRightMeters);
- bb.putDouble(value.rearLeftMeters);
- bb.putDouble(value.rearRightMeters);
+ bb.putDouble(value.frontLeft);
+ bb.putDouble(value.frontRight);
+ bb.putDouble(value.rearLeft);
+ bb.putDouble(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.java
index 66956541fc6..8d2f6382bcc 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.java
@@ -40,9 +40,9 @@ public MecanumDriveWheelSpeeds unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, MecanumDriveWheelSpeeds value) {
- bb.putDouble(value.frontLeftMetersPerSecond);
- bb.putDouble(value.frontRightMetersPerSecond);
- bb.putDouble(value.rearLeftMetersPerSecond);
- bb.putDouble(value.rearRightMetersPerSecond);
+ bb.putDouble(value.frontLeft);
+ bb.putDouble(value.frontRight);
+ bb.putDouble(value.rearLeft);
+ bb.putDouble(value.rearRight);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModulePositionStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModulePositionStruct.java
index 6fff1cbb778..85ebdc47c3c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModulePositionStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModulePositionStruct.java
@@ -44,7 +44,7 @@ public SwerveModulePosition unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, SwerveModulePosition value) {
- bb.putDouble(value.distanceMeters);
+ bb.putDouble(value.distance);
Rotation2d.struct.pack(bb, value.angle);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModuleStateStruct.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModuleStateStruct.java
index af29a8d628f..90c538221d9 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModuleStateStruct.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/struct/SwerveModuleStateStruct.java
@@ -44,7 +44,7 @@ public SwerveModuleState unpack(ByteBuffer bb) {
@Override
public void pack(ByteBuffer bb, SwerveModuleState value) {
- bb.putDouble(value.speedMetersPerSecond);
+ bb.putDouble(value.speed);
Rotation2d.struct.pack(bb, value.angle);
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java b/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
index 94ab7616d00..c51ef56c1f5 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/spline/PoseWithCurvature.java
@@ -9,24 +9,24 @@
/** Represents a pair of a pose and a curvature. */
public class PoseWithCurvature {
/** Represents the pose. */
- public Pose2d poseMeters;
+ public Pose2d pose;
- /** Represents the curvature. */
- public double curvatureRadPerMeter;
+ /** Represents the curvature in radians per meter. */
+ public double curvature;
/**
* Constructs a PoseWithCurvature.
*
- * @param poseMeters The pose.
- * @param curvatureRadPerMeter The curvature.
+ * @param pose The pose.
+ * @param curvature The curvature in radians per meter.
*/
- public PoseWithCurvature(Pose2d poseMeters, double curvatureRadPerMeter) {
- this.poseMeters = poseMeters;
- this.curvatureRadPerMeter = curvatureRadPerMeter;
+ public PoseWithCurvature(Pose2d pose, double curvature) {
+ this.pose = pose;
+ this.curvature = curvature;
}
/** Constructs a PoseWithCurvature with default values. */
public PoseWithCurvature() {
- poseMeters = Pose2d.kZero;
+ pose = Pose2d.kZero;
}
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
index b08c8c78a8b..bc63d1a6726 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineParameterizer.java
@@ -126,7 +126,7 @@ public static List parameterize(Spline spline, double t0, dou
throw new MalformedSplineException(kMalformedSplineExceptionMsg);
}
- final var twist = start.get().poseMeters.log(end.get().poseMeters);
+ final var twist = start.get().pose.log(end.get().pose);
if (Math.abs(twist.dy) > kMaxDy
|| Math.abs(twist.dx) > kMaxDx
|| Math.abs(twist.dtheta) > kMaxDtheta) {
diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java b/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
index b4afdf476af..978a2f3c115 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/system/Discretization.java
@@ -20,13 +20,13 @@ private Discretization() {
*
* @param Num representing the number of states.
* @param contA Continuous system matrix.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @return the discrete matrix system.
*/
public static Matrix discretizeA(
- Matrix contA, double dtSeconds) {
+ Matrix contA, double dt) {
// A_d = eᴬᵀ
- return contA.times(dtSeconds).exp();
+ return contA.times(dt).exp();
}
/**
@@ -36,12 +36,12 @@ public static Matrix discretizeA(
* @param Nat representing the inputs to the system.
* @param contA Continuous system matrix.
* @param contB Continuous input matrix.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @return a Pair representing discA and diskB.
*/
public static
Pair, Matrix> discretizeAB(
- Matrix contA, Matrix contB, double dtSeconds) {
+ Matrix contA, Matrix contB, double dt) {
int states = contA.getNumRows();
int inputs = contB.getNumCols();
@@ -53,7 +53,7 @@ Pair, Matrix> discretizeAB(
// ϕ = eᴹᵀ = [A_d B_d]
// [ 0 I ]
- var phi = M.times(dtSeconds).exp();
+ var phi = M.times(dt).exp();
var discA = new Matrix(new SimpleMatrix(states, states));
discA.extractFrom(0, 0, phi);
@@ -70,12 +70,12 @@ Pair, Matrix> discretizeAB(
* @param Nat representing the number of states.
* @param contA Continuous system matrix.
* @param contQ Continuous process noise covariance matrix.
- * @param dtSeconds Discretization timestep.
+ * @param dt Discretization timestep in seconds.
* @return a pair representing the discrete system matrix and process noise covariance matrix.
*/
public static
Pair, Matrix> discretizeAQ(
- Matrix contA, Matrix contQ, double dtSeconds) {
+ Matrix