Skip to content
Merged
Show file tree
Hide file tree
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 @@ -10,7 +10,6 @@
import static java.util.Map.entry;

import edu.wpi.first.units.VoltageUnit;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.units.measure.Time;
import edu.wpi.first.units.measure.Velocity;
import edu.wpi.first.units.measure.Voltage;
Expand Down Expand Up @@ -42,7 +41,6 @@
public class SysIdRoutine extends SysIdRoutineLog {
private final Config m_config;
private final Mechanism m_mechanism;
private final MutVoltage m_outputVolts = Volts.mutable(0);
private final Consumer<State> m_recordState;

/**
Expand Down Expand Up @@ -225,9 +223,7 @@ public Command quasistatic(Direction direction) {
m_mechanism.m_subsystem.run(
() -> {
m_mechanism.m_drive.accept(
m_outputVolts.mut_replace(
outputSign * timer.get() * m_config.m_rampRate.in(Volts.per(Second)),
Volts));
(Voltage) m_config.m_rampRate.times(Seconds.of(timer.get() * outputSign)));
m_mechanism.m_log.accept(this);
m_recordState.accept(state);
}))
Expand Down Expand Up @@ -258,15 +254,15 @@ public Command dynamic(Direction direction) {
entry(Direction.kForward, State.kDynamicForward),
entry(Direction.kReverse, State.kDynamicReverse))
.get(direction);
Voltage[] output = {Volts.zero()};

return m_mechanism
.m_subsystem
.runOnce(
() -> m_outputVolts.mut_replace(m_config.m_stepVoltage.in(Volts) * outputSign, Volts))
.runOnce(() -> output[0] = m_config.m_stepVoltage.times(outputSign))
.andThen(
m_mechanism.m_subsystem.run(
() -> {
m_mechanism.m_drive.accept(m_outputVolts);
m_mechanism.m_drive.accept(output[0]);
m_mechanism.m_log.accept(this);
m_recordState.accept(state);
}))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,6 @@
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.Volts;

import edu.wpi.first.units.measure.MutDistance;
import edu.wpi.first.units.measure.MutLinearVelocity;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
Expand Down Expand Up @@ -46,13 +43,6 @@ public class Drive extends SubsystemBase {
DriveConstants.kRightEncoderPorts[1],
DriveConstants.kRightEncoderReversed);

// Mutable holder for unit-safe voltage values, persisted to avoid reallocation.
private final MutVoltage m_appliedVoltage = Volts.mutable(0);
// Mutable holder for unit-safe linear distance values, persisted to avoid reallocation.
private final MutDistance m_distance = Meters.mutable(0);
// Mutable holder for unit-safe linear velocity values, persisted to avoid reallocation.
private final MutLinearVelocity m_velocity = MetersPerSecond.mutable(0);

// Create a new SysId routine for characterizing the drive.
private final SysIdRoutine m_sysIdRoutine =
new SysIdRoutine(
Expand All @@ -70,21 +60,15 @@ public class Drive extends SubsystemBase {
// Record a frame for the left motors. Since these share an encoder, we consider
// the entire group to be one motor.
log.motor("drive-left")
.voltage(
m_appliedVoltage.mut_replace(
m_leftMotor.get() * RobotController.getBatteryVoltage(), Volts))
.linearPosition(m_distance.mut_replace(m_leftEncoder.getDistance(), Meters))
.linearVelocity(
m_velocity.mut_replace(m_leftEncoder.getRate(), MetersPerSecond));
.voltage(Volts.of(m_leftMotor.get() * RobotController.getBatteryVoltage()))
.linearPosition(Meters.of(m_leftEncoder.getDistance()))
.linearVelocity(MetersPerSecond.of(m_leftEncoder.getRate()));
// Record a frame for the right motors. Since these share an encoder, we consider
// the entire group to be one motor.
log.motor("drive-right")
.voltage(
m_appliedVoltage.mut_replace(
m_rightMotor.get() * RobotController.getBatteryVoltage(), Volts))
.linearPosition(m_distance.mut_replace(m_rightEncoder.getDistance(), Meters))
.linearVelocity(
m_velocity.mut_replace(m_rightEncoder.getRate(), MetersPerSecond));
.voltage(Volts.of(m_rightMotor.get() * RobotController.getBatteryVoltage()))
.linearPosition(Meters.of(m_rightEncoder.getDistance()))
.linearVelocity(MetersPerSecond.of(m_rightEncoder.getRate()));
},
// Tell SysId to make generated commands require this subsystem, suffix test state in
// WPILog with this subsystem's name ("drive")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,12 @@

package edu.wpi.first.wpilibj.examples.sysidroutine.subsystems;

import static edu.wpi.first.units.Units.Radians;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import static edu.wpi.first.units.Units.Volts;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.units.measure.MutAngle;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.examples.sysidroutine.Constants.ShooterConstants;
Expand All @@ -38,13 +33,6 @@ public class Shooter extends SubsystemBase {
ShooterConstants.kEncoderPorts[1],
ShooterConstants.kEncoderReversed);

// Mutable holder for unit-safe voltage values, persisted to avoid reallocation.
private final MutVoltage m_appliedVoltage = Volts.mutable(0);
// Mutable holder for unit-safe linear distance values, persisted to avoid reallocation.
private final MutAngle m_angle = Radians.mutable(0);
// Mutable holder for unit-safe linear velocity values, persisted to avoid reallocation.
private final MutAngularVelocity m_velocity = RadiansPerSecond.mutable(0);

// Create a new SysId routine for characterizing the shooter.
private final SysIdRoutine m_sysIdRoutine =
new SysIdRoutine(
Expand All @@ -58,12 +46,9 @@ public class Shooter extends SubsystemBase {
log -> {
// Record a frame for the shooter motor.
log.motor("shooter-wheel")
.voltage(
m_appliedVoltage.mut_replace(
m_shooterMotor.get() * RobotController.getBatteryVoltage(), Volts))
.angularPosition(m_angle.mut_replace(m_shooterEncoder.getDistance(), Rotations))
.angularVelocity(
m_velocity.mut_replace(m_shooterEncoder.getRate(), RotationsPerSecond));
.voltage(Volts.of(m_shooterMotor.get() * RobotController.getBatteryVoltage()))
.angularPosition(Rotations.of(m_shooterEncoder.getDistance()))
.angularVelocity(RotationsPerSecond.of(m_shooterEncoder.getRate()));
},
// Tell SysId to make generated commands require this subsystem, suffix test state in
// WPILog with this subsystem's name ("shooter")
Expand Down
30 changes: 7 additions & 23 deletions wpiunits/generate_units.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ def output(output_dir, outfn: str, contents: str):
"divide": {"Time": "AngularAcceleration"},
"extra": inspect.cleandoc(
"""
default Frequency asFrequency() { return Hertz.of(baseUnitMagnitude()); }
public Frequency asFrequency() { return Hertz.of(baseUnitMagnitude()); }
"""
),
},
Expand Down Expand Up @@ -164,7 +164,7 @@ def output(output_dir, outfn: str, contents: str):
"extra": inspect.cleandoc(
"""
/** Converts this frequency to the time period between cycles. */
default Time asPeriod() { return Seconds.of(1 / baseUnitMagnitude()); }
public Time asPeriod() { return Seconds.of(1 / baseUnitMagnitude()); }
"""
),
},
Expand Down Expand Up @@ -206,11 +206,11 @@ def output(output_dir, outfn: str, contents: str):
"divide": {},
"extra": inspect.cleandoc(
"""
default Measure<Dividend> timesDivisor(Measure<? extends Divisor> multiplier) {
public Measure<Dividend> timesDivisor(Measure<? extends Divisor> multiplier) {
return (Measure<Dividend>) baseUnit().numerator().ofBaseUnits(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
}

default Measure<? extends PerUnit<Divisor, Dividend>> reciprocal() {
public Measure<? extends PerUnit<Divisor, Dividend>> reciprocal() {
// May return a velocity if Divisor == TimeUnit, so we can't guarantee a "Per" instance
return baseUnit().reciprocal().ofBaseUnits(1 / baseUnitMagnitude());
}
Expand Down Expand Up @@ -252,7 +252,7 @@ def output(output_dir, outfn: str, contents: str):
},
"extra": inspect.cleandoc(
"""
default Frequency asFrequency() { return Hertz.of(1 / baseUnitMagnitude()); }
public Frequency asFrequency() { return Hertz.of(1 / baseUnitMagnitude()); }
"""
),
},
Expand All @@ -269,7 +269,7 @@ def output(output_dir, outfn: str, contents: str):
"implementation": inspect.cleandoc(
"""
@Override
default Measure<D> times(Time multiplier) {
public Measure<D> times(Time multiplier) {
return (Measure<D>) unit().numerator().ofBaseUnits(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
}
"""
Expand Down Expand Up @@ -352,9 +352,7 @@ def generate_units(output_directory: Path, template_directory: Path):
keep_trailing_newline=True,
)

interfaceTemplate = env.get_template("Measure-interface.java.jinja")
immutableTemplate = env.get_template("Measure-immutable.java.jinja")
mutableTemplate = env.get_template("Measure-mutable.java.jinja")
interfaceTemplate = env.get_template("Measure-implementation.java.jinja")
rootPath = output_directory / "main/java/edu/wpi/first/units"

helpers = {
Expand All @@ -373,22 +371,8 @@ def generate_units(output_directory: Path, template_directory: Path):
config=UNIT_CONFIGURATIONS,
helpers=helpers,
)
immutableContents = immutableTemplate.render(
name=unit_name,
units=MATH_OPERATION_UNITS,
config=UNIT_CONFIGURATIONS,
helpers=helpers,
)
mutableContents = mutableTemplate.render(
name=unit_name,
units=MATH_OPERATION_UNITS,
config=UNIT_CONFIGURATIONS,
helpers=helpers,
)

output(rootPath / "measure", f"{unit_name}.java", interfaceContents)
output(rootPath / "measure", f"Immutable{unit_name}.java", immutableContents)
output(rootPath / "measure", f"Mut{unit_name}.java", mutableContents)


def main():
Expand Down
28 changes: 0 additions & 28 deletions wpiunits/src/generate/main/java/Measure-immutable.java.jinja

This file was deleted.

Loading
Loading