Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add unit overloads for DCMotor set/get input voltage #7185

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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. */
Expand All @@ -43,6 +45,9 @@ public class DCMotorSim extends LinearSystemSim<N2, N1, N2> {
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.
*
Expand Down Expand Up @@ -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 getInputVoltageMeasure() {
m_voltage.mut_setMagnitude(getInputVoltage());
return m_voltage;
}

/**
* Sets the input voltage for the DC motor.
*
Expand All @@ -252,4 +267,13 @@ 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) {
daltzctr marked this conversation as resolved.
Show resolved Hide resolved
setInputVoltage(volts.in(Volts));
}
}
Loading