Skip to content

Commit

Permalink
[wpimath] Remove unit suffixes from variable names
Browse files Browse the repository at this point in the history
* Move units into API docs instead because suffixes make user code verbose and hard to read
* Rename trackWidth to trackwidth
* Make ultrasonic classes use meters instead of a mix of m, cm, mm, ft,
  and inches
  • Loading branch information
calcmogul committed Dec 9, 2024
1 parent b6ae9e9 commit 51264de
Show file tree
Hide file tree
Showing 250 changed files with 2,612 additions and 3,283 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
9 changes: 4 additions & 5 deletions hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,10 @@ public class DMAJNI extends JNIWrapper {
* <p>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.
Expand Down Expand Up @@ -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.
Expand Down
4 changes: 2 additions & 2 deletions hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
Original file line number Diff line number Diff line change
Expand Up @@ -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];
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@

#include <gtest/gtest.h>

#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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ public class MecanumControllerCommand extends Command {
private final MecanumDriveKinematics m_kinematics;
private final HolonomicDriveController m_controller;
private final Supplier<Rotation2d> 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;
Expand Down Expand Up @@ -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.
Expand All @@ -98,7 +98,7 @@ public MecanumControllerCommand(
PIDController yController,
ProfiledPIDController thetaController,
Supplier<Rotation2d> desiredRotation,
double maxWheelVelocityMetersPerSecond,
double maxWheelVelocity,
PIDController frontLeftController,
PIDController rearLeftController,
PIDController frontRightController,
Expand All @@ -120,7 +120,7 @@ public MecanumControllerCommand(
m_desiredRotation =
requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");

m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
m_maxWheelVelocity = maxWheelVelocity;

m_frontLeftController =
requireNonNullParam(frontLeftController, "frontLeftController", "MecanumControllerCommand");
Expand Down Expand Up @@ -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.
Expand All @@ -184,7 +184,7 @@ public MecanumControllerCommand(
PIDController xController,
PIDController yController,
ProfiledPIDController thetaController,
double maxWheelVelocityMetersPerSecond,
double maxWheelVelocity,
PIDController frontLeftController,
PIDController rearLeftController,
PIDController frontRightController,
Expand All @@ -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,
Expand All @@ -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.
*/
Expand All @@ -241,7 +240,7 @@ public MecanumControllerCommand(
PIDController yController,
ProfiledPIDController thetaController,
Supplier<Rotation2d> desiredRotation,
double maxWheelVelocityMetersPerSecond,
double maxWheelVelocity,
Consumer<MecanumDriveWheelSpeeds> outputWheelSpeeds,
Subsystem... requirements) {
m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand");
Expand All @@ -258,7 +257,7 @@ public MecanumControllerCommand(
m_desiredRotation =
requireNonNullParam(desiredRotation, "desiredRotation", "MecanumControllerCommand");

m_maxWheelVelocityMetersPerSecond = maxWheelVelocityMetersPerSecond;
m_maxWheelVelocity = maxWheelVelocity;

m_frontLeftController = null;
m_rearLeftController = null;
Expand Down Expand Up @@ -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.
*/
Expand All @@ -307,7 +306,7 @@ public MecanumControllerCommand(
PIDController xController,
PIDController yController,
ProfiledPIDController thetaController,
double maxWheelVelocityMetersPerSecond,
double maxWheelVelocity,
Consumer<MecanumDriveWheelSpeeds> outputWheelSpeeds,
Subsystem... requirements) {
this(
Expand All @@ -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);
}
Expand All @@ -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();
}
Expand All @@ -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;
Expand All @@ -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(
Expand All @@ -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());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down Expand Up @@ -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);
}
Expand Down Expand Up @@ -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());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -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() {
Expand All @@ -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
Expand All @@ -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(
Expand All @@ -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;
Expand All @@ -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));
}
Expand Down
Loading

0 comments on commit 51264de

Please sign in to comment.