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

Java units API rewrite #6958

Merged
merged 47 commits into from
Sep 7, 2024
Merged
Show file tree
Hide file tree
Changes from 32 commits
Commits
Show all changes
47 commits
Select commit Hold shift + click to select a range
5112c36
Rename unit classes to end in *Unit
SamCarlberg Jun 14, 2024
869a2c4
Flatten units into discrete types
SamCarlberg Jun 15, 2024
fb61fc7
Rename `IMutable` to `MutableMeasure`
SamCarlberg Jun 20, 2024
cd04e93
Move mutable types to dedicated package
SamCarlberg Jun 25, 2024
485135a
Split into mutable and immutable variants
SamCarlberg Jun 26, 2024
158c576
Small fixups
SamCarlberg Jun 26, 2024
fd0d2d1
Move measure interfaces to their own package
SamCarlberg Jun 26, 2024
29b1e68
Implement toString for immutable measures
SamCarlberg Jun 26, 2024
542b0f6
Misc cleanup
SamCarlberg Jun 27, 2024
a44bf47
Add generic constructor to trapezoid profile constraints
SamCarlberg Jun 27, 2024
38d18ba
Add ratio measure type
SamCarlberg Jun 27, 2024
d23b27f
Add math operator overloads for all known dimensions
SamCarlberg Jun 28, 2024
0e6c8d0
Formatting and linting
SamCarlberg Jun 28, 2024
acfea50
Linting, documentation, and seal nonextensible unit types
SamCarlberg Jun 29, 2024
ab96bf3
Fix import ordering
SamCarlberg Jun 29, 2024
04cb95a
Improve `equals` logic
SamCarlberg Jun 29, 2024
d44ac50
Checkstyle
SamCarlberg Aug 13, 2024
88ecf04
Consistent API in unit subclasses for non-inherited methods
SamCarlberg Aug 13, 2024
0405dff
Refactor usages of old unit APIs
SamCarlberg Aug 13, 2024
2f7cd05
Add wpiunits to pregenerated files CI check
SamCarlberg Aug 13, 2024
90da7a9
Doc fix
SamCarlberg Aug 13, 2024
4c71208
Remove unused import from codegen script
SamCarlberg Aug 13, 2024
0e7a055
Update epilogue logging
SamCarlberg Aug 13, 2024
6fefb1c
Update cmake build
SamCarlberg Aug 13, 2024
1239fb6
Linting
SamCarlberg Aug 13, 2024
a5c821c
Fix some combined base units
SamCarlberg Aug 13, 2024
469d8dc
Add standard zero() and one() factories
SamCarlberg Aug 15, 2024
ef5b23e
Fix Newton definition
SamCarlberg Aug 15, 2024
10081d6
Suppress this-escape warning
SamCarlberg Aug 22, 2024
e20ee8e
Update EpilogueConfiguration
SamCarlberg Aug 22, 2024
3d5134a
Formatting fixes
github-actions[bot] Aug 22, 2024
a08c350
Return sharpened types from `one()` and `zero()` methods
SamCarlberg Aug 28, 2024
65e2c8c
Fix docs typo
SamCarlberg Aug 28, 2024
d7f42e1
Add a `timesConversionFactor()` method
SamCarlberg Aug 28, 2024
055b409
Add Per.timesDivisor() and Per.reciprocal()
SamCarlberg Aug 28, 2024
bbc7784
Basic script documentation
SamCarlberg Aug 28, 2024
ed9204a
Merge remote-tracking branch 'wpi/main' into unit-flattening
SamCarlberg Aug 28, 2024
eedcea4
Remove Force.mult(Distance) -> Energy function for now
SamCarlberg Aug 28, 2024
f1d9dc2
Revert example project constants
SamCarlberg Sep 2, 2024
10bb1af
Use `Measure` input parameters consistently
SamCarlberg Sep 2, 2024
5de0ae9
Add .ofNative factories to PerUnit
SamCarlberg Sep 3, 2024
9d2e419
Linting
SamCarlberg Sep 3, 2024
4d4e61c
Fix derived name/symbol indicating division instead of multiplication
SamCarlberg Sep 3, 2024
7365901
Add simple tests for PerUnit
SamCarlberg Sep 3, 2024
6bb4513
Consistently use dimension-specific measure types wherever possible
SamCarlberg Sep 4, 2024
bcdac63
Add .ofNative to MultUnit
SamCarlberg Sep 4, 2024
2140dec
Linting
SamCarlberg Sep 5, 2024
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
2 changes: 2 additions & 0 deletions .github/workflows/pregenerate.yml
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ jobs:
run: ./ntcore/generate_topics.py
- name: Run wpimath
run: ./wpimath/generate_numbers.py && ./wpimath/generate_quickbuf.py --quickbuf_plugin=protoc-gen-quickbuf-1.3.3-linux-x86_64.exe
- name: Run wpiunits
run: ./wpiunits/generate_units.py
- name: Run HIDs
run: ./wpilibj/generate_hids.py && ./wpilibc/generate_hids.py && ./wpilibNewCommands/generate_hids.py
- name: Run PWM Controllers
Expand Down
5 changes: 4 additions & 1 deletion docs/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,10 @@ task generateJavaDocs(type: Javadoc) {
"-edu.wpi.first.math.system.struct," +
"-edu.wpi.first.math.system.plant.proto," +
"-edu.wpi.first.math.system.plant.struct," +
"-edu.wpi.first.math.trajectory.proto", true)
"-edu.wpi.first.math.trajectory.proto," +
// The .measure package contains generated source files for which automatic javadoc
// generation is very difficult to do meaningfully.
"-edu.wpi.first.units.measure", true)
options.addBooleanOption("Xdoclint:html,missing,reference,syntax", true)
options.addBooleanOption('html5', true)
options.linkSource(true)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,7 @@
import edu.wpi.first.epilogue.logging.errors.ErrorHandler;
import edu.wpi.first.epilogue.logging.errors.ErrorPrinter;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.measure.Time;

/**
* A configuration object to be used by the generated {@code Epilogue} class to customize its
Expand All @@ -29,13 +28,13 @@ public class EpilogueConfiguration {
* The period Epilogue will log at. By default this is the period that the robot runs at. This is
* the field used by bind to configure speed when adding the periodic logging function
*/
public Measure<Time> loggingPeriod;
public Time loggingPeriod;

/**
* The offset from the periodic run that Epilogue will log at. By default this will be half of the
* robots period. This is the field used by bind when adding the periodic logging function
*/
public Measure<Time> loggingPeriodOffset;
public Time loggingPeriodOffset;

/**
* The minimum importance level of data to be logged. Defaults to debug, which logs data of all
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ default void log(String identifier, Measure<?> value) {
* @param unit the unit to log the measurement in
* @param <U> the dimension of the unit
*/
default <U extends Unit<U>> void log(String identifier, Measure<U> value, U unit) {
default <U extends Unit> void log(String identifier, Measure<U> value, U unit) {
log(identifier, value.in(unit));
}

Expand Down
2 changes: 2 additions & 0 deletions styleguide/checkstyle-suppressions.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,6 @@ suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN"
checks="(CustomImportOrder|EmptyLineSeparator|LineLength|JavadocParagraph|MissingJavadocMethod|OverloadMethodsDeclarationOrder|SummaryJavadoc|UnnecessaryParentheses|OperatorWrap|JavadocMethod|JavadocTagContinuationIndentation)" />
<suppress files="wpilibj[/\\]src[/\\]generated.*"
checks="MethodName" />
<!-- Disable checkstyle for generated unit files -->
<suppress files="wpiunits[/\\]src[/\\]generated.*" checks=".*"/>
</suppressions>
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,10 @@

package edu.wpi.first.wpilibj2.command;

import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.measure.Time;
import edu.wpi.first.util.function.BooleanConsumer;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
Expand Down Expand Up @@ -179,8 +178,8 @@ public ParallelRaceGroup withTimeout(double seconds) {
* @param time the timeout duration
* @return the command with the timeout added
*/
public ParallelRaceGroup withTimeout(Measure<Time> time) {
return withTimeout(time.in(Second));
public ParallelRaceGroup withTimeout(Time time) {
return withTimeout(time.in(Seconds));
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,7 @@

import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;

import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.measure.Time;
import java.util.Map;
import java.util.Set;
import java.util.function.BooleanSupplier;
Expand Down Expand Up @@ -137,7 +136,7 @@ public static Command waitSeconds(double seconds) {
* @return the command
* @see WaitCommand
*/
public static Command waitTime(Measure<Time> time) {
public static Command waitTime(Time time) {
return new WaitCommand(time);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,7 @@
import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.MutableMeasure;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.units.measure.MutLinearVelocity;
import edu.wpi.first.wpilibj.Timer;
import java.util.function.Consumer;
import java.util.function.Supplier;
Expand Down Expand Up @@ -60,22 +58,14 @@ public class MecanumControllerCommand extends Command {
private final Supplier<MecanumDriveWheelSpeeds> m_currentWheelSpeeds;
private final Consumer<MecanumDriveMotorVoltages> m_outputDriveVoltages;
private final Consumer<MecanumDriveWheelSpeeds> m_outputWheelSpeeds;
private final MutableMeasure<Velocity<Distance>> m_prevFrontLeftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_prevRearLeftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_prevFrontRightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_prevRearRightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_frontLeftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_rearLeftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_frontRightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_rearRightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutLinearVelocity m_prevFrontLeftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_prevRearLeftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_prevFrontRightSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_prevRearRightSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_frontLeftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_rearLeftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_frontRightSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_rearRightSpeedSetpoint = MetersPerSecond.mutable(0);

/**
* Constructs a new MecanumControllerCommand that when executed will follow the provided
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,7 @@
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.units.Distance;
import edu.wpi.first.units.MutableMeasure;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.units.measure.MutLinearVelocity;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.Timer;
import java.util.function.BiConsumer;
Expand Down Expand Up @@ -51,14 +49,10 @@ public class RamseteCommand extends Command {
private final PIDController m_rightController;
private final BiConsumer<Double, Double> m_output;
private DifferentialDriveWheelSpeeds m_prevSpeeds = new DifferentialDriveWheelSpeeds();
private final MutableMeasure<Velocity<Distance>> m_prevLeftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_prevRightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_leftSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutableMeasure<Velocity<Distance>> m_rightSpeedSetpoint =
MutableMeasure.zero(MetersPerSecond);
private final MutLinearVelocity m_prevLeftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_prevRightSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_leftSpeedSetpoint = MetersPerSecond.mutable(0);
private final MutLinearVelocity m_rightSpeedSetpoint = MetersPerSecond.mutable(0);
private double m_prevTime;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,9 @@

package edu.wpi.first.wpilibj2.command;

import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;

import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.measure.Time;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Timer;
Expand Down Expand Up @@ -39,8 +38,8 @@ public WaitCommand(double seconds) {
*
* @param time the time to wait
*/
public WaitCommand(Measure<Time> time) {
this(time.in(Second));
public WaitCommand(Time time) {
this(time.in(Seconds));
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,16 @@

package edu.wpi.first.wpilibj2.command.sysid;

import static edu.wpi.first.units.MutableMeasure.mutable;
import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.units.Units.Volts;
import static java.util.Map.entry;

import edu.wpi.first.units.Measure;
import edu.wpi.first.units.MutableMeasure;
import edu.wpi.first.units.Time;
import edu.wpi.first.units.Velocity;
import edu.wpi.first.units.Voltage;
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;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -43,7 +42,7 @@
public class SysIdRoutine extends SysIdRoutineLog {
private final Config m_config;
private final Mechanism m_mechanism;
private final MutableMeasure<Voltage> m_outputVolts = mutable(Volts.of(0));
private final MutVoltage m_outputVolts = Volts.mutable(0);
private final Consumer<State> m_recordState;

/**
Expand All @@ -62,13 +61,13 @@ public SysIdRoutine(Config config, Mechanism mechanism) {
/** Hardware-independent configuration for a SysId test routine. */
public static class Config {
/** The voltage ramp rate used for quasistatic test routines. */
public final Measure<Velocity<Voltage>> m_rampRate;
public final Velocity<VoltageUnit> m_rampRate;

/** The step voltage output used for dynamic test routines. */
public final Measure<Voltage> m_stepVoltage;
public final Voltage m_stepVoltage;

/** Safety timeout for the test routine commands. */
public final Measure<Time> m_timeout;
public final Time m_timeout;

/** Optional handle for recording test state in a third-party logging solution. */
public final Consumer<State> m_recordState;
Expand All @@ -87,11 +86,11 @@ public static class Config {
* logged in WPILog.
*/
public Config(
Measure<Velocity<Voltage>> rampRate,
Measure<Voltage> stepVoltage,
Measure<Time> timeout,
Velocity<VoltageUnit> rampRate,
Voltage stepVoltage,
Time timeout,
Consumer<State> recordState) {
m_rampRate = rampRate != null ? rampRate : Volts.of(1).per(Seconds.of(1));
m_rampRate = rampRate != null ? rampRate : Volts.of(1).per(Second);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does per() no longer take a quantity but rather a unit type?

m_stepVoltage = stepVoltage != null ? stepVoltage : Volts.of(7);
m_timeout = timeout != null ? timeout : Seconds.of(10);
m_recordState = recordState;
Expand All @@ -107,8 +106,7 @@ public Config(
* @param timeout Safety timeout for the test routine commands. Defaults to 10 seconds if left
* null.
*/
public Config(
Measure<Velocity<Voltage>> rampRate, Measure<Voltage> stepVoltage, Measure<Time> timeout) {
public Config(Velocity<VoltageUnit> rampRate, Voltage stepVoltage, Time timeout) {
this(rampRate, stepVoltage, timeout, null);
}

Expand All @@ -132,7 +130,7 @@ public Config() {
*/
public static class Mechanism {
/** Sends the SysId-specified drive signal to the mechanism motors during test routines. */
public final Consumer<Measure<Voltage>> m_drive;
public final Consumer<? super Voltage> m_drive;

/**
* Returns measured data (voltages, positions, velocities) of the mechanism motors during test
Expand Down Expand Up @@ -163,10 +161,7 @@ public static class Mechanism {
* the subsystem if left null.
*/
public Mechanism(
Consumer<Measure<Voltage>> drive,
Consumer<SysIdRoutineLog> log,
Subsystem subsystem,
String name) {
Consumer<Voltage> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem, String name) {
m_drive = drive;
m_log = log != null ? log : l -> {};
m_subsystem = subsystem;
Expand All @@ -189,8 +184,7 @@ public Mechanism(
* will be appended to the log entry title for the routine's test state, e.g.
* "sysid-test-state-subsystem".
*/
public Mechanism(
Consumer<Measure<Voltage>> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem) {
public Mechanism(Consumer<Voltage> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem) {
this(drive, log, subsystem, null);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

import edu.wpi.first.hal.HAL;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.Voltage;
import edu.wpi.first.units.VoltageUnit;
import edu.wpi.first.wpilibj.simulation.SimHooks;
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -28,7 +28,7 @@ class SysIdRoutineTest {
interface Mechanism extends Subsystem {
void recordState(SysIdRoutineLog.State state);

void drive(Measure<Voltage> voltage);
void drive(Measure<VoltageUnit> voltage);

void log(SysIdRoutineLog log);
}
Expand Down
Loading