From c065ae1fcf9515218f594741c375b530882387a2 Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sun, 23 Jul 2023 17:18:17 -0400 Subject: [PATCH] [wpiunits] Add subproject for a Java typesafe unit system (#5371) # Background Unit safety has always been a problem in WPILib. Any value corresponding to a physical measurement, such as current draw or distance traveled, is represented by a bare number with no unit tied to it; it's up to the programmer to know what units they're working and take care to remember that while working on their robot program. This leads to bugs when programmers accidentally mix units without knowing, or measure something (such as a wheel diameter) in one unit and program using another. `wpiunits` is intended to eliminate that class of bugs. Another source of friction is the controllers and models in `wpimath` that expect all inputs to be in terms of SI units (meter, kilogram, and so on), while most FRC teams are US-based and most commonly use imperial units. wpimath does a good job of noting unit types in method names and argument names; however, it still relies on users properly converting values (and knowing they even have to do so). # API There are really only two core classes in this library: `Unit` and `Measure`. A `Unit` represents some dimension like distance or time. `Unit` is subclassed to define specific dimensions (eg `Distance` and `Time`) and those subclasses are instantiated to defined particular units in those dimensions, such as `Meters` and `Feet` being instances of the `Distance` class. A `Measure` is a value tied to a particular dimension like distance and knows what unit that value is tied to. `Measure` has two implementations - one immutable and one mutable. The `Measure` interface only defines *read-only* operations; any API working with measurements should use the interface. The default implementation is `ImmutableMeasure`, which only implements those read-only operations and is useful for tracking constants. `MutableMeasure` also adds some methods that will allow for mutation of its internal state; this class is intended for use for things like sensors and controllers that track internal state and don't want to allocate new `Measure` objects every time something like `myEncoder.getDistance()` is called. However, the APIs for those methods should still only expose the read-only `Measure` interface so users can't (without casting or reflection) change the internal values. A `Units` class provides convenient definitions for most of the commonly used unit types, such as `Meters`, `Feet`, and `Milliseconds`. I recommend static importing these units eg `import static edu.wpi.first.units.Units.Meters`) so they can be used like `Meters.of(1.234)` instead of `Units.Meters.of(1.234)` # Examples These examples are admittedly contrived. Users shouldn't be interacting much with measure objects themselves, since wpimath and wpilibj classes will be updated to support working with them; users will often just have to take a `Measure` output from one place (such as an encoder) and feed it as input to something else (such as a PID controller or kinematics model) ```java // Using raw units Encoder encoder = ... int kPulsesPerRev = 2048; double kWheelDiameterMeters = Units.inchesToMeters(6); double kGearRatio = 10.86; // always have to remember this encoder will output in meters! encoder.setDistancePerPulse(kWheelDiameterMeters * Math.PI / (kGearRatio * kPulsesPerRev)); Command driveDistance(double distance) { // have to know the distance argument needs to be in meters! return run(this::driveStraight).until(() -> encoder.getDistance() >= distance); } // Oops! This will go 16 feet, not 5! Command driveFiveFeet = driveDistance(5); Command driveOneMeter = driveDistance(1); ``` ```java // Using wpiunits Encoder encoder = ... int kPulsesPerRev = 2048; Measure kWheelDiameter = Inches.of(6); double kGearRatio = 10.86; encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev)); Command driveDistance(Measure distance) { // Measure#gte automatically handles unit conversions return run(this::driveStraight).until(() -> encoder.getDistance().gte(distance)); } // Users HAVE to be explicit about their units Command driveFiveFeet = driveDistance(Feet.of(5)); Command driveOneMeter = driveDistance(Meters.of(1)); ``` ```java SmartDashboard.putNumber("Temperature (C)", pdp.getTemperature().in(Celsius)); SmartDashboard.putNumber("Temperature (F)", pdp.getTemperature().in(Fahrenheit)); ``` ```java var InchSecond = Inch.mult(Second); // new combined unit types can be user-defined var InchPerSecond = Inch.per(Second); PIDController heightController = new PIDController<>( /* kP */ Volts.of(0.2).per(Inch), /* kI */ Volts.of(0.002).per(InchSecond), /* kD */ Volts.of(0.008).per(InchPerSecond) ); var elevatorTop = Feet.of(4).plus(Inches.of(6.125)); elevatorMotor.setVoltage(heightController.calculate(encoder.getDistance(), elevatorTop)); ``` --- docs/build.gradle | 1 + settings.gradle | 1 + wpiunits/build.gradle | 14 + .../dev/java/edu/wpi/first/units/DevMain.java | 14 + .../main/java/edu/wpi/first/units/Angle.java | 26 ++ .../java/edu/wpi/first/units/BaseUnits.java | 45 +++ .../java/edu/wpi/first/units/Current.java | 20 + .../edu/wpi/first/units/Dimensionless.java | 26 ++ .../java/edu/wpi/first/units/Distance.java | 17 + .../main/java/edu/wpi/first/units/Energy.java | 16 + .../edu/wpi/first/units/ImmutableMeasure.java | 110 ++++++ .../main/java/edu/wpi/first/units/Mass.java | 16 + .../java/edu/wpi/first/units/Measure.java | 353 ++++++++++++++++++ .../main/java/edu/wpi/first/units/Mult.java | 95 +++++ .../edu/wpi/first/units/MutableMeasure.java | 302 +++++++++++++++ .../main/java/edu/wpi/first/units/Per.java | 103 +++++ .../main/java/edu/wpi/first/units/Power.java | 16 + .../java/edu/wpi/first/units/Temperature.java | 12 + .../main/java/edu/wpi/first/units/Time.java | 16 + .../edu/wpi/first/units/UnaryFunction.java | 77 ++++ .../main/java/edu/wpi/first/units/Unit.java | 296 +++++++++++++++ .../java/edu/wpi/first/units/UnitBuilder.java | 216 +++++++++++ .../main/java/edu/wpi/first/units/Units.java | 207 ++++++++++ .../java/edu/wpi/first/units/Velocity.java | 156 ++++++++ .../java/edu/wpi/first/units/Voltage.java | 20 + .../collections/LongToObjectHashMap.java | 332 ++++++++++++++++ .../collections/ReadOnlyPrimitiveLongSet.java | 125 +++++++ .../java/edu/wpi/first/units/CurrentTest.java | 26 ++ .../edu/wpi/first/units/DistanceTest.java | 34 ++ .../java/edu/wpi/first/units/EncoderTest.java | 92 +++++ .../java/edu/wpi/first/units/ExampleUnit.java | 19 + .../java/edu/wpi/first/units/MeasureTest.java | 312 ++++++++++++++++ .../java/edu/wpi/first/units/MultTest.java | 37 ++ .../wpi/first/units/MutableMeasureTest.java | 133 +++++++ .../wpi/first/units/UnaryFunctionTest.java | 102 +++++ .../java/edu/wpi/first/units/UnitTest.java | 19 + .../java/edu/wpi/first/units/UnitsTest.java | 348 +++++++++++++++++ .../edu/wpi/first/units/VelocityTest.java | 58 +++ .../java/edu/wpi/first/units/VoltageTest.java | 23 ++ .../collections/LongToObjectHashMapTest.java | 96 +++++ 40 files changed, 3931 insertions(+) create mode 100644 wpiunits/build.gradle create mode 100644 wpiunits/src/dev/java/edu/wpi/first/units/DevMain.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Angle.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/BaseUnits.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Current.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Dimensionless.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Distance.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Energy.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/ImmutableMeasure.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Mass.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Measure.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Mult.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/MutableMeasure.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Per.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Power.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Temperature.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Time.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/UnaryFunction.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Unit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/UnitBuilder.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Units.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Velocity.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Voltage.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/collections/LongToObjectHashMap.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/collections/ReadOnlyPrimitiveLongSet.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/CurrentTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/DistanceTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/EncoderTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/ExampleUnit.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/MultTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/MutableMeasureTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/UnaryFunctionTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/UnitTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/UnitsTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/VelocityTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/VoltageTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/collections/LongToObjectHashMapTest.java diff --git a/docs/build.gradle b/docs/build.gradle index 6ef7c6da96..78b2c106e4 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -13,6 +13,7 @@ evaluationDependsOn(':wpilibc') evaluationDependsOn(':wpilibj') evaluationDependsOn(':wpimath') evaluationDependsOn(':wpinet') +evaluationDependsOn(':wpiunits') evaluationDependsOn(':wpiutil') def baseArtifactIdCpp = 'documentation' diff --git a/settings.gradle b/settings.gradle index 6ae1063e89..f6d097cbfb 100644 --- a/settings.gradle +++ b/settings.gradle @@ -33,6 +33,7 @@ include 'wpilibcIntegrationTests' include 'wpilibjExamples' include 'wpilibjIntegrationTests' include 'wpilibj' +include 'wpiunits' include 'crossConnIntegrationTests' include 'fieldImages' include 'glass' diff --git a/wpiunits/build.gradle b/wpiunits/build.gradle new file mode 100644 index 0000000000..e10033df6a --- /dev/null +++ b/wpiunits/build.gradle @@ -0,0 +1,14 @@ +ext { + useJava = true + useCpp = false + baseId = 'wpiunits' + groupId = 'edu.wpi.first.wpiunits' + + nativeName = 'wpiunits' + devMain = 'edu.wpi.first.units.DevMain' +} + +apply from: "${rootDir}/shared/java/javacommon.gradle" + +dependencies { +} diff --git a/wpiunits/src/dev/java/edu/wpi/first/units/DevMain.java b/wpiunits/src/dev/java/edu/wpi/first/units/DevMain.java new file mode 100644 index 0000000000..0d4dcdd2a4 --- /dev/null +++ b/wpiunits/src/dev/java/edu/wpi/first/units/DevMain.java @@ -0,0 +1,14 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +public final class DevMain { + /** Main entry point. */ + public static void main(String[] args) { + System.out.println(Units.Inches.of(-5.0).in(Units.Meters)); + } + + private DevMain() {} +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Angle.java b/wpiunits/src/main/java/edu/wpi/first/units/Angle.java new file mode 100644 index 0000000000..105a935575 --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Angle.java @@ -0,0 +1,26 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +// technically, angles are unitless dimensions +// eg Mass * Distance * Velocity is equivalent to (Mass * Distance) / Time - otherwise known +// as Power - in other words, Velocity is /actually/ Frequency +public class Angle extends Unit { + /** + * Creates a new unit with the given name and multiplier to the base unit. + * + * @param baseUnitEquivalent the multiplier to convert this unit to the base unit of this type + * @param name the name of the angle measure + * @param symbol the symbol of the angle measure + */ + Angle(double baseUnitEquivalent, String name, String symbol) { + super(Angle.class, baseUnitEquivalent, name, symbol); + } + + Angle( + UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Angle.class, toBaseConverter, fromBaseConverter, name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/BaseUnits.java b/wpiunits/src/main/java/edu/wpi/first/units/BaseUnits.java new file mode 100644 index 0000000000..5e342da121 --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/BaseUnits.java @@ -0,0 +1,45 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +/** The base units of measure. */ +public final class BaseUnits { + private BaseUnits() { + // Prevent instantiation + } + + /** The standard unit of distance, meters. */ + public static final Distance Distance = new Distance(1, "Meter", "m"); + + /** The standard unit of time, seconds. */ + public static final Time Time = new Time(1, "Second", "s"); + + /** The standard unit of velocity, meters per second. */ + public static final Velocity Velocity = + new Velocity<>(Distance, Time, "Meter per Second", "m/s"); + + /** The standard unit of mass, grams. */ + public static final Mass Mass = new Mass(1, "Kilogram", "Kg"); + + /** The standard unit of angles, revolutions. */ + public static final Angle Angle = new Angle(1, "Revolution", "R"); + + /** The standard "unitless" unit. */ + public static final Dimensionless Value = new Dimensionless(1, "", ""); + + /** The standard unit of voltage, volts. */ + public static final Voltage Voltage = new Voltage(1, "Volt", "V"); + + /** The standard unit of electric current, amperes. */ + public static final Current Current = new Current(1, "Amp", "A"); + + /** The standard unit of energy, joules. */ + public static final Energy Energy = new Energy(1, "Joule", "J"); + + /** The standard unit of power, watts. */ + public static final Power Power = new Power(1, "Watt", "W"); + + public static final Temperature Temperature = new Temperature(x -> x, x -> x, "Kelvin", "K"); +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Current.java b/wpiunits/src/main/java/edu/wpi/first/units/Current.java new file mode 100644 index 0000000000..88418c5106 --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Current.java @@ -0,0 +1,20 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +public class Current extends Unit { + Current(double baseUnitEquivalent, String name, String symbol) { + super(Current.class, baseUnitEquivalent, name, symbol); + } + + Current( + UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Current.class, toBaseConverter, fromBaseConverter, name, symbol); + } + + public Power times(Unit voltage, String name, String symbol) { + return new Power(this.toBaseUnits(1) * voltage.toBaseUnits(1), name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Dimensionless.java b/wpiunits/src/main/java/edu/wpi/first/units/Dimensionless.java new file mode 100644 index 0000000000..5d1772f79b --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Dimensionless.java @@ -0,0 +1,26 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +/** + * A type of unit that corresponds to raw values and not any physical dimension, such as percentage. + */ +public class Dimensionless extends Unit { + /** + * Creates a new unit with the given name and multiplier to the base unit. + * + * @param baseUnitEquivalent the multiplier to convert this unit to the base unit of this type. + * @param name the name of the unit + * @param symbol the symbol of the unit + */ + protected Dimensionless(double baseUnitEquivalent, String name, String symbol) { + super(Dimensionless.class, baseUnitEquivalent, name, symbol); + } + + Dimensionless( + UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Dimensionless.class, toBaseConverter, fromBaseConverter, name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Distance.java b/wpiunits/src/main/java/edu/wpi/first/units/Distance.java new file mode 100644 index 0000000000..d5512ddddd --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Distance.java @@ -0,0 +1,17 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +public class Distance extends Unit { + /** Creates a new unit with the given name and multiplier to the base unit. */ + Distance(double baseUnitEquivalent, String name, String symbol) { + super(Distance.class, baseUnitEquivalent, name, symbol); + } + + Distance( + UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Distance.class, toBaseConverter, fromBaseConverter, name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Energy.java b/wpiunits/src/main/java/edu/wpi/first/units/Energy.java new file mode 100644 index 0000000000..d43adf9cd9 --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Energy.java @@ -0,0 +1,16 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +public class Energy extends Unit { + protected Energy( + UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Energy.class, toBaseConverter, fromBaseConverter, name, symbol); + } + + protected Energy(double baseUnitEquivalent, String name, String symbol) { + super(Energy.class, baseUnitEquivalent, name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/ImmutableMeasure.java b/wpiunits/src/main/java/edu/wpi/first/units/ImmutableMeasure.java new file mode 100644 index 0000000000..84fb732149 --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/ImmutableMeasure.java @@ -0,0 +1,110 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +import java.util.Objects; + +/** + * A measure holds the magnitude and unit of some dimension, such as distance, time, or speed. A + * measure is immutable and type safe, making it easy to use in concurrent situations + * and gives compile-time safety. Two measures with the same unit and magnitude are + * effectively the same object. + * + * @param the unit type of the measure + */ +public class ImmutableMeasure> implements Measure { + private final double m_magnitude; + private final double m_baseUnitMagnitude; + private final U m_unit; + + /** + * Creates a new immutable measure instance. This shouldn't be used directly; prefer one of the + * factory methods instead. + * + * @param magnitude the magnitude of this measure + * @param unit the unit of this measure. + */ + @SuppressWarnings("unchecked") + ImmutableMeasure(double magnitude, double baseUnitMagnitude, Unit unit) { + Objects.requireNonNull(unit, "Unit cannot be null"); + m_magnitude = magnitude; + m_baseUnitMagnitude = baseUnitMagnitude; + m_unit = (U) unit; + } + + /** + * Creates a new measure in the given unit with a magnitude equal to the given one in base units. + * + * @param the type of the units of measure + * @param baseUnitMagnitude the magnitude of the measure, in terms of the base unit of measure + * @param unit the unit of measure + * @return a new measure + */ + public static > ImmutableMeasure ofBaseUnits( + double baseUnitMagnitude, Unit unit) { + return new ImmutableMeasure<>(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit); + } + + /** + * Creates a new measure in the given unit with a magnitude in terms of that unit. + * + * @param the type of the units of measure + * @param relativeMagnitude the magnitude of the measure + * @param unit the unit of measure + * @return a new measure + */ + public static > ImmutableMeasure ofRelativeUnits( + double relativeMagnitude, Unit unit) { + return new ImmutableMeasure<>(relativeMagnitude, unit.toBaseUnits(relativeMagnitude), unit); + } + + /** Gets the unitless magnitude of this measure. */ + @Override + public double magnitude() { + return m_magnitude; + } + + @Override + public double baseUnitMagnitude() { + return m_baseUnitMagnitude; + } + + /** Gets the units of this measure. */ + @Override + public U unit() { + return m_unit; + } + + /** + * Checks for object equality. To check if two measures are equivalent, use {@link + * #isEquivalent(Measure) isEquivalent}. + */ + @Override + public boolean equals(Object o) { + if (this == o) { + return true; + } + if (!(o instanceof Measure)) { + return false; + } + Measure that = (Measure) o; + return Objects.equals(m_unit, that.unit()) && m_baseUnitMagnitude == that.baseUnitMagnitude(); + } + + @Override + public int hashCode() { + return Objects.hash(m_magnitude, m_unit); + } + + @Override + public Measure copy() { + return this; // already immutable, no need to allocate a new object + } + + @Override + public String toString() { + return toShortString(); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Mass.java b/wpiunits/src/main/java/edu/wpi/first/units/Mass.java new file mode 100644 index 0000000000..c9dc0bbe1e --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Mass.java @@ -0,0 +1,16 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +public class Mass extends Unit { + /** Creates a new unit with the given name and multiplier to the base unit. */ + Mass(double baseUnitEquivalent, String name, String symbol) { + super(Mass.class, baseUnitEquivalent, name, symbol); + } + + Mass(UnaryFunction toBaseConverter, UnaryFunction fromBaseConverter, String name, String symbol) { + super(Mass.class, toBaseConverter, fromBaseConverter, name, symbol); + } +} diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Measure.java b/wpiunits/src/main/java/edu/wpi/first/units/Measure.java new file mode 100644 index 0000000000..2decf37cfc --- /dev/null +++ b/wpiunits/src/main/java/edu/wpi/first/units/Measure.java @@ -0,0 +1,353 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.units; + +/** + * A measure holds the magnitude and unit of some dimension, such as distance, time, or speed. Two + * measures with the same unit and magnitude are effectively the same object. + * + * @param the unit type of the measure + */ +public interface Measure> extends Comparable> { + /** + * The threshold for two measures to be considered equivalent if converted to the same unit. This + * is only needed due to floating-point error. + */ + double EQUIVALENCE_THRESHOLD = 1e-12; + + /** Gets the unitless magnitude of this measure. */ + double magnitude(); + + /** Gets the magnitude of this measure in terms of the base unit. */ + double baseUnitMagnitude(); + + /** Gets the units of this measure. */ + U unit(); + + /** + * Converts this measure to a measure with a different unit of the same type, eg minutes to + * seconds. Converting to the same unit is equivalent to calling {@link #magnitude()}. + * + *
+   *   Meters.of(12).in(Feet) // => 39.3701
+   *   Seconds.of(15).in(Minutes) // => 0.25
+   * 
+ * + * @param unit the unit to convert this measure to + * @return the value of this measure in the given unit + */ + default double in(Unit unit) { + if (this.unit().equals(unit)) { + return magnitude(); + } else { + return unit.fromBaseUnits(baseUnitMagnitude()); + } + } + + /** + * Multiplies this measurement by some constant multiplier and returns the result. + * + * @param multiplier the constant to multiply by + */ + default Measure times(double multiplier) { + return ImmutableMeasure.ofBaseUnits(baseUnitMagnitude() * multiplier, unit()); + } + + /** + * Generates a new measure that is equal to this measure multiplied by another. Some dimensional + * analysis is performed to reduce the units down somewhat; for example, multiplying a {@code + * Measure