From 3b190f46b464d77f9b504366b474330c27f477ab Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 10 Dec 2024 12:48:42 -0800 Subject: [PATCH] Address review comments --- .../first/wpilibj/simulation/ElevatorSim.java | 16 ++++++++-------- .../wpilibj/simulation/LinearSystemSim.java | 2 +- .../wpilibj/simulation/SingleJointedArmSim.java | 4 ++-- .../ultrasonicpid/UltrasonicPIDTest.java | 2 +- .../first/math/estimator/KalmanTypeFilter.java | 2 +- .../wpi/first/math/kinematics/ChassisSpeeds.java | 14 +++++++------- .../kinematics/DifferentialDriveKinematics.java | 4 ++-- .../edu/wpi/first/math/system/plant/DCMotor.java | 4 ++-- .../wpi/first/math/trajectory/Trajectory.java | 2 +- 9 files changed, 25 insertions(+), 25 deletions(-) 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 c5d80589410..085a46bb08b 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 minHeight The min allowable height of the elevator. - * @param maxHeight The max allowable height of the elevator. + * @param minHeight The min allowable height of the elevator in meters. + * @param maxHeight The max allowable height of the elevator in meters. * @param simulateGravity Whether gravity should be simulated or not. - * @param startingHeight The starting height of the elevator. + * @param startingHeight The starting height of the elevator in meters. * @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no * noise is desired. If present must have 1 element for position. */ @@ -98,8 +98,8 @@ 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 carriageMass The mass of the elevator carriage. - * @param drumRadius The radius of the drum that the elevator spool is wrapped around. + * @param carriageMass The mass of the elevator carriage in kg. + * @param drumRadius The radius of the drum that the elevator spool is wrapped around in meters. * @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. @@ -141,7 +141,7 @@ public final void setState(double position, double velocity) { /** * Returns whether the elevator would hit the lower limit. * - * @param elevatorHeight The elevator height. + * @param elevatorHeight The elevator height in meters. * @return Whether the elevator would hit the lower limit. */ public boolean wouldHitLowerLimit(double elevatorHeight) { @@ -151,7 +151,7 @@ public boolean wouldHitLowerLimit(double elevatorHeight) { /** * Returns whether the elevator would hit the upper limit. * - * @param elevatorHeight The elevator height. + * @param elevatorHeight The elevator height in meters. * @return Whether the elevator would hit the upper limit. */ public boolean wouldHitUpperLimit(double elevatorHeight) { @@ -226,7 +226,7 @@ public void setInputVoltage(double volts) { * * @param currentXhat The current state estimate. * @param u The system inputs (voltage). - * @param dt 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 dt) { 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 65270a24a64..87ecdae577f 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 @@ -171,7 +171,7 @@ public void setState(Matrix state) { * * @param currentXhat The current state estimate. * @param u The system inputs (usually voltage). - * @param dt The time difference between controller updates. + * @param dt The time difference between controller updates in seconds. * @return The new state. */ protected Matrix updateX( 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 318b3c179ee..35b93ebbd16 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 @@ -164,7 +164,7 @@ public boolean hasHitUpperLimit() { * * @return The current arm angle in radians. */ - public double getAngleRads() { + public double getAngle() { return getOutput(0); } @@ -180,7 +180,7 @@ public double getVelocity() { /** * Returns the arm current draw. * - * @return The arm current draw. + * @return The arm current draw in amps. */ public double getCurrentDraw() { // Reductions are greater than 1, so a reduction of 10:1 would mean the motor is 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 9c5cf5360d2..add8dba9e9b 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 @@ -28,7 +28,7 @@ class UltrasonicPIDTest { private final DCMotor m_gearbox = DCMotor.getFalcon500(2); private static final double kGearing = KitbotGearing.k10p71.value; public static final double kvLinear = 1.98; // V/(m/s) - public static final double kaLinear = 0.2; // 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 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 a072be98e14..e1dcf0dd2f8 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,7 +76,7 @@ public interface KalmanTypeFilter u, double dt); 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 8b375538b3d..b684581b895 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 @@ -65,9 +65,9 @@ public ChassisSpeeds(double vx, double vy, double omega) { /** * Constructs a ChassisSpeeds object. * - * @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 vx Forward velocity. + * @param vy Sideways velocity. + * @param omega Angular velocity. */ public ChassisSpeeds(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) { this(vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond)); @@ -126,10 +126,10 @@ public static ChassisSpeeds discretize(double vx, double vy, double omega, doubl *

This is useful for compensating for translational skew when translating and rotating a * swerve drivetrain. * - * @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. + * @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. * @return Discretized ChassisSpeeds. * @deprecated Use instance method instead. */ 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 766a0522b55..359e020840b 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 @@ -100,8 +100,8 @@ 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 leftDistance The distance measured by the left side encoder. - * @param rightDistance The distance measured by the right side encoder. + * @param leftDistance The distance measured by the left side encoder in meters. + * @param rightDistance The distance measured by the right side encoder in meters. * @return The resulting Twist2d. */ public Twist2d toTwist2d(double leftDistance, double rightDistance) { diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java index 2d25cec2f15..9fb001221ca 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/plant/DCMotor.java @@ -94,8 +94,8 @@ public double getCurrent(double torque) { /** * Calculate torque produced by the motor with a given current. * - * @param current The current drawn by the motor. - * @return The torque output. + * @param current The current drawn by the motor in amps. + * @return The torque output in Newton-meters. */ public double getTorque(double current) { return current * Kt; diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java index f8e1adc385e..bea2261febd 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/Trajectory.java @@ -84,7 +84,7 @@ public Pose2d getInitialPose() { /** * Returns the overall duration of the trajectory. * - * @return The duration of the trajectory. + * @return The duration of the trajectory in seconds. */ public double getTotalTime() { return m_totalTime;