From d92ef25c0d56d9b39500eaa4f927c5eee9f3fee8 Mon Sep 17 00:00:00 2001 From: Dalton Smith <105223895+daltzctr@users.noreply.github.com> Date: Fri, 11 Oct 2024 11:43:27 -0400 Subject: [PATCH 1/3] Add unit overloads for DCMotor set/get input voltage --- .../first/wpilibj/simulation/DCMotorSim.java | 25 +++++++++++++++++++ 1 file changed, 25 insertions(+) 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 4440a2d7787..02a99f90e84 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 @@ -7,6 +7,7 @@ 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 static edu.wpi.first.units.Units.Volts; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.numbers.N1; @@ -20,6 +21,7 @@ import edu.wpi.first.units.measure.MutAngle; import edu.wpi.first.units.measure.MutAngularAcceleration; import edu.wpi.first.units.measure.MutAngularVelocity; +import edu.wpi.first.units.measure.Voltage; import edu.wpi.first.wpilibj.RobotController; /** Represents a simulated DC motor mechanism. */ @@ -43,6 +45,9 @@ public class DCMotorSim extends LinearSystemSim { private final MutAngularAcceleration m_angularAcceleration = RadiansPerSecondPerSecond.mutable(0.0); + // Input voltage of the system + private final MutVoltage m_voltage = Volts.mutable(0); + /** * Creates a simulated DC motor mechanism. * @@ -243,6 +248,16 @@ public double getInputVoltage() { return getInput(0); } + /** + * Gets the input voltage for the DC motor. + * + * @return The DC motor's input voltage. + */ + public Voltage getInputVoltageVolts() { + m_voltage.mut_setMagnitude(getInput(0)); + return m_voltage; + } + /** * Sets the input voltage for the DC motor. * @@ -252,4 +267,14 @@ public void setInputVoltage(double volts) { setInput(volts); clampInput(RobotController.getBatteryVoltage()); } + + /** + * Sets the input voltage for the DC motor. + * + * @param volts The input voltage. + */ + public void setInputVoltage(Voltage volts) { + setInput(volts.in(Volts)); + clampInput(RobotController.getBatteryVoltage()); + } } From 2c4ed8acc8b243d90afffe657fd4cacfaa2bfa47 Mon Sep 17 00:00:00 2001 From: Dalton Smith <105223895+daltzctr@users.noreply.github.com> Date: Fri, 11 Oct 2024 12:00:37 -0400 Subject: [PATCH 2/3] Address review comments --- .../java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) 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 02a99f90e84..00521a552b3 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 @@ -254,7 +254,7 @@ public double getInputVoltage() { * @return The DC motor's input voltage. */ public Voltage getInputVoltageVolts() { - m_voltage.mut_setMagnitude(getInput(0)); + m_voltage.mut_setMagnitude(getInputVoltage()); return m_voltage; } @@ -274,7 +274,6 @@ public void setInputVoltage(double volts) { * @param volts The input voltage. */ public void setInputVoltage(Voltage volts) { - setInput(volts.in(Volts)); - clampInput(RobotController.getBatteryVoltage()); + setInputVoltage(volts.in(Volts)); } } From aed2601dc34adb8f3c23da42079c20955f1991b5 Mon Sep 17 00:00:00 2001 From: Dalton Smith <105223895+daltzctr@users.noreply.github.com> Date: Fri, 11 Oct 2024 12:57:23 -0400 Subject: [PATCH 3/3] Rename getter function --- .../main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 00521a552b3..53b19271751 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 @@ -253,7 +253,7 @@ public double getInputVoltage() { * * @return The DC motor's input voltage. */ - public Voltage getInputVoltageVolts() { + public Voltage getInputVoltageMeasure() { m_voltage.mut_setMagnitude(getInputVoltage()); return m_voltage; }