[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
// 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;
|
|
|
|
|
|
|
|
|
|
/**
|
2023-11-23 12:57:58 -06:00
|
|
|
* Unit of measurement that defines a quantity, such as grams, meters, or seconds.
|
|
|
|
|
*
|
|
|
|
|
* <p>This is the base class for units. Actual units (such as {@link Units#Grams} and {@link
|
|
|
|
|
* Units#Meters}) can be found in the {@link Units} class.
|
[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
*
|
|
|
|
|
* @param <U> the self type, e.g. {@code class SomeUnit extends Unit<SomeUnit>}
|
|
|
|
|
*/
|
|
|
|
|
public class Unit<U extends Unit<U>> {
|
|
|
|
|
private final UnaryFunction m_toBaseConverter;
|
|
|
|
|
private final UnaryFunction m_fromBaseConverter;
|
|
|
|
|
|
|
|
|
|
final Class<? extends U> m_baseType; // package-private for the builder
|
|
|
|
|
|
|
|
|
|
private Measure<U> m_zero;
|
|
|
|
|
private Measure<U> m_one;
|
|
|
|
|
|
|
|
|
|
private final String m_name;
|
|
|
|
|
private final String m_symbol;
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates a new unit defined by its relationship to some base unit.
|
|
|
|
|
*
|
|
|
|
|
* @param baseType the base type of the unit, e.g. Distance.class for the distance unit
|
|
|
|
|
* @param toBaseConverter a function for converting units of this type to the base unit
|
|
|
|
|
* @param fromBaseConverter a function for converting units of the base unit to this one
|
|
|
|
|
* @param name the name of the unit. This should be a singular noun (so "Meter", not "Meters")
|
|
|
|
|
* @param symbol the short symbol for the unit, such as "m" for meters or "lb." for pounds
|
|
|
|
|
*/
|
|
|
|
|
protected Unit(
|
|
|
|
|
Class<? extends U> baseType,
|
|
|
|
|
UnaryFunction toBaseConverter,
|
|
|
|
|
UnaryFunction fromBaseConverter,
|
|
|
|
|
String name,
|
|
|
|
|
String symbol) {
|
|
|
|
|
m_baseType = Objects.requireNonNull(baseType);
|
|
|
|
|
m_toBaseConverter = Objects.requireNonNull(toBaseConverter);
|
|
|
|
|
m_fromBaseConverter = Objects.requireNonNull(fromBaseConverter);
|
|
|
|
|
m_name = Objects.requireNonNull(name);
|
|
|
|
|
m_symbol = Objects.requireNonNull(symbol);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates a new unit with the given name and multiplier to the base unit.
|
|
|
|
|
*
|
|
|
|
|
* @param baseType the base type of the unit, e.g. Distance.class for the distance unit
|
|
|
|
|
* @param baseUnitEquivalent the multiplier to convert this unit to the base unit of this type.
|
|
|
|
|
* For example, meters has a multiplier of 1, mm has a multiplier of 1e3, and km has
|
|
|
|
|
* multiplier of 1e-3.
|
|
|
|
|
* @param name the name of the unit. This should be a singular noun (so "Meter", not "Meters")
|
|
|
|
|
* @param symbol the short symbol for the unit, such as "m" for meters or "lb." for pounds
|
|
|
|
|
*/
|
|
|
|
|
protected Unit(
|
|
|
|
|
Class<? extends U> baseType, double baseUnitEquivalent, String name, String symbol) {
|
|
|
|
|
this(baseType, x -> x * baseUnitEquivalent, x -> x / baseUnitEquivalent, name, symbol);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Converts a value in terms of base units to a value in terms of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @param valueInBaseUnits the value in base units to convert
|
|
|
|
|
* @return the equivalent value in terms of this unit
|
|
|
|
|
*/
|
|
|
|
|
public double fromBaseUnits(double valueInBaseUnits) {
|
|
|
|
|
return m_fromBaseConverter.apply(valueInBaseUnits);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Converts a value in terms of this unit to a value in terms of the base unit.
|
|
|
|
|
*
|
|
|
|
|
* @param valueInNativeUnits the value in terms of this unit to convert
|
|
|
|
|
* @return the equivalent value in terms of the base unit
|
|
|
|
|
*/
|
|
|
|
|
public double toBaseUnits(double valueInNativeUnits) {
|
|
|
|
|
return m_toBaseConverter.apply(valueInNativeUnits);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Converts a magnitude in terms of another unit of the same dimension to a magnitude in terms of
|
|
|
|
|
* this unit.
|
|
|
|
|
*
|
|
|
|
|
* <pre>
|
2023-10-20 18:14:14 -07:00
|
|
|
* Inches.convertFrom(12, Feet) // 144.0
|
|
|
|
|
* Kilograms.convertFrom(2.2, Pounds) // 0.9979024
|
[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
* </pre>
|
|
|
|
|
*
|
|
|
|
|
* @param magnitude a magnitude measured in another unit
|
|
|
|
|
* @param otherUnit the unit to convert the magnitude to
|
2023-10-20 18:14:14 -07:00
|
|
|
* @return the corresponding value in terms of this unit.
|
[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
*/
|
|
|
|
|
public double convertFrom(double magnitude, Unit<U> otherUnit) {
|
|
|
|
|
if (this.equivalent(otherUnit)) {
|
|
|
|
|
// same unit, don't bother converting
|
|
|
|
|
return magnitude;
|
|
|
|
|
}
|
|
|
|
|
return this.fromBaseUnits(otherUnit.toBaseUnits(magnitude));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets the conversion function used to convert values to base unit terms. This generally
|
|
|
|
|
* shouldn't need to be used directly; prefer {@link #toBaseUnits(double)} instead.
|
|
|
|
|
*
|
|
|
|
|
* @return the conversion function
|
|
|
|
|
*/
|
|
|
|
|
public UnaryFunction getConverterToBase() {
|
|
|
|
|
return m_toBaseConverter;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets the conversion function used to convert values to terms of this unit. This generally
|
|
|
|
|
* shouldn't need to be used directly; prefer {@link #fromBaseUnits(double)} instead.
|
|
|
|
|
*
|
|
|
|
|
* @return the conversion function
|
|
|
|
|
*/
|
|
|
|
|
public UnaryFunction getConverterFromBase() {
|
|
|
|
|
return m_fromBaseConverter;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates a new measure of this unit with the given value. The resulting measure is
|
|
|
|
|
* <i>immutable</i> and cannot have its value modified.
|
|
|
|
|
*
|
|
|
|
|
* @param magnitude the magnitude of the measure to create
|
2023-10-20 18:14:14 -07:00
|
|
|
* @return the measure
|
[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
*/
|
|
|
|
|
public Measure<U> of(double magnitude) {
|
|
|
|
|
if (magnitude == 0) {
|
|
|
|
|
// reuse static object
|
|
|
|
|
return zero();
|
|
|
|
|
}
|
|
|
|
|
if (magnitude == 1) {
|
|
|
|
|
// reuse static object
|
|
|
|
|
return one();
|
|
|
|
|
}
|
|
|
|
|
return ImmutableMeasure.ofRelativeUnits(magnitude, this);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates a new measure with a magnitude equal to the given base unit magnitude, converted to be
|
|
|
|
|
* in terms of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @param baseUnitMagnitude the magnitude of the measure in terms of the base unit
|
|
|
|
|
* @return the measure
|
|
|
|
|
*/
|
|
|
|
|
public Measure<U> ofBaseUnits(double baseUnitMagnitude) {
|
|
|
|
|
return ImmutableMeasure.ofBaseUnits(baseUnitMagnitude, this);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets a measure with a magnitude of 0 in terms of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @return the zero-valued measure
|
|
|
|
|
*/
|
|
|
|
|
public Measure<U> zero() {
|
|
|
|
|
// lazy init because 'this' is null in object initialization
|
|
|
|
|
if (m_zero == null) {
|
|
|
|
|
m_zero = ImmutableMeasure.ofRelativeUnits(0, this);
|
|
|
|
|
}
|
|
|
|
|
return m_zero;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets a measure with a magnitude of 1 in terms of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @return the 1-valued measure
|
|
|
|
|
*/
|
|
|
|
|
public Measure<U> one() {
|
|
|
|
|
// lazy init because 'this' is null in object initialization
|
|
|
|
|
if (m_one == null) {
|
|
|
|
|
m_one = ImmutableMeasure.ofRelativeUnits(1, this);
|
|
|
|
|
}
|
|
|
|
|
return m_one;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates a velocity unit derived from this one. Can be chained to denote velocity, acceleration,
|
|
|
|
|
* jerk, etc.
|
|
|
|
|
*
|
|
|
|
|
* <pre>
|
2023-10-20 18:14:14 -07:00
|
|
|
* Meters.per(Second) // linear velocity
|
|
|
|
|
* Kilograms.per(Second) // mass flow
|
[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<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> 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<Distance, ElectricPotential> 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));
```
2023-07-23 17:18:17 -04:00
|
|
|
* Feet.per(Second).per(Second).of(32) // roughly 1G of acceleration
|
|
|
|
|
* </pre>
|
|
|
|
|
*
|
|
|
|
|
* @param period the time period of the velocity, such as seconds or milliseconds
|
|
|
|
|
* @return a velocity unit corresponding to the rate of change of this unit over time
|
|
|
|
|
*/
|
|
|
|
|
public Velocity<U> per(Time period) {
|
|
|
|
|
return Velocity.combine(this, period);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Takes this unit and creates a new proportional unit where this unit is the numerator and the
|
|
|
|
|
* given denominator is the denominator.
|
|
|
|
|
*
|
|
|
|
|
* <pre>
|
|
|
|
|
* Volts.per(Meter) // V/m
|
|
|
|
|
* </pre>
|
|
|
|
|
*
|
|
|
|
|
* @param <D> the type of the denominator units
|
|
|
|
|
* @param denominator the denominator of the proportional unit
|
|
|
|
|
* @return a combined proportional unit
|
|
|
|
|
*/
|
|
|
|
|
@SuppressWarnings("unchecked")
|
|
|
|
|
public <D extends Unit<D>> Per<U, D> per(D denominator) {
|
|
|
|
|
return Per.combine((U) this, denominator);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Takes this unit and creates a new combinatory unit equivalent to this unit multiplied by
|
|
|
|
|
* another.
|
|
|
|
|
*
|
|
|
|
|
* <pre>
|
|
|
|
|
* Volts.mult(Meter) // V*m
|
|
|
|
|
* </pre>
|
|
|
|
|
*
|
|
|
|
|
* @param <U2> the type of the unit to multiply by
|
|
|
|
|
* @param other the unit to multiply by
|
|
|
|
|
* @return a combined unit equivalent to this unit multiplied by the other
|
|
|
|
|
*/
|
|
|
|
|
@SuppressWarnings("unchecked")
|
|
|
|
|
public <U2 extends Unit<U2>> Mult<U, U2> mult(U2 other) {
|
|
|
|
|
return Mult.combine((U) this, other);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Checks if this unit is equivalent to another one. Equivalence is determined by both units
|
|
|
|
|
* having the same base type and treat the same base unit magnitude as the same magnitude in their
|
|
|
|
|
* own units, to within {@link Measure#EQUIVALENCE_THRESHOLD}.
|
|
|
|
|
*
|
|
|
|
|
* @param other the unit to compare to.
|
|
|
|
|
* @return true if both units are equivalent, false if not
|
|
|
|
|
*/
|
|
|
|
|
public boolean equivalent(Unit<?> other) {
|
|
|
|
|
if (this.m_baseType != other.m_baseType) {
|
|
|
|
|
// different unit types, not compatible
|
|
|
|
|
return false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
double arbitrary = 16_777.214; // 2^24 / 1e3
|
|
|
|
|
|
|
|
|
|
return Math.abs(
|
|
|
|
|
this.m_fromBaseConverter.apply(arbitrary)
|
|
|
|
|
- other.m_fromBaseConverter.apply(arbitrary))
|
|
|
|
|
<= Measure.EQUIVALENCE_THRESHOLD
|
|
|
|
|
&& Math.abs(
|
|
|
|
|
this.m_toBaseConverter.apply(arbitrary) - other.m_toBaseConverter.apply(arbitrary))
|
|
|
|
|
<= Measure.EQUIVALENCE_THRESHOLD;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Override
|
|
|
|
|
public boolean equals(Object o) {
|
|
|
|
|
if (this == o) {
|
|
|
|
|
return true;
|
|
|
|
|
}
|
|
|
|
|
if (!(o instanceof Unit)) {
|
|
|
|
|
return false;
|
|
|
|
|
}
|
|
|
|
|
Unit<?> that = (Unit<?>) o;
|
|
|
|
|
return m_baseType.equals(that.m_baseType)
|
|
|
|
|
&& m_name.equals(that.m_name)
|
|
|
|
|
&& m_symbol.equals(that.m_symbol)
|
|
|
|
|
&& this.equivalent(that);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Override
|
|
|
|
|
public int hashCode() {
|
|
|
|
|
return Objects.hash(m_toBaseConverter, m_fromBaseConverter, m_baseType, m_name, m_symbol);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets the name of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @return the unit's name
|
|
|
|
|
*/
|
|
|
|
|
public String name() {
|
|
|
|
|
return m_name;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Gets the symbol of this unit.
|
|
|
|
|
*
|
|
|
|
|
* @return the unit's symbol
|
|
|
|
|
*/
|
|
|
|
|
public String symbol() {
|
|
|
|
|
return m_symbol;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Override
|
|
|
|
|
public String toString() {
|
|
|
|
|
return name();
|
|
|
|
|
}
|
|
|
|
|
}
|