Skip to content

Commit

Permalink
Address review comments
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul committed Dec 10, 2024
1 parent d539dda commit 3b190f4
Show file tree
Hide file tree
Showing 9 changed files with 25 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N2> {
* {@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.
*/
Expand Down Expand Up @@ -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.
Expand Down Expand Up @@ -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) {
Expand All @@ -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) {
Expand Down Expand Up @@ -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<N2, N1> updateX(Matrix<N2, N1> currentXhat, Matrix<N1, N1> u, double dt) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ public void setState(Matrix<States, N1> 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<States, N1> updateX(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ public boolean hasHitUpperLimit() {
*
* @return The current arm angle in radians.
*/
public double getAngleRads() {
public double getAngle() {
return getOutput(0);
}

Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ public interface KalmanTypeFilter<States extends Num, Inputs extends Num, Output
* Project the model into the future with a new control input u.
*
* @param u New control input from controller.
* @param dt Timestep for prediction.
* @param dt Timestep for prediction in seconds.
*/
void predict(Matrix<Inputs, N1> u, double dt);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand Down Expand Up @@ -126,10 +126,10 @@ public static ChassisSpeeds discretize(double vx, double vy, double omega, doubl
* <p>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.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 3b190f4

Please sign in to comment.