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

[wpilibj] Add wpiunits subproject for a typesafe unit system #5371

Merged
merged 22 commits into from
Jul 23, 2023

Conversation

SamCarlberg
Copy link
Member

@SamCarlberg SamCarlberg commented Jun 1, 2023

Currently exists as a standalone project with nothing depending on it. Will be used by wpimath and wpilibj. Using a separate project to allow easy reuse between projects and for publishing for vendor use.

This is large enough that I'll be doing wpimath and wpilibj in a followup PR


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)

// 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);
// 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));
SmartDashboard.putNumber("Temperature (C)", pdp.getTemperature().in(Celsius));
SmartDashboard.putNumber("Temperature (F)", pdp.getTemperature().in(Fahrenheit));
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));

Comment on lines +35 to +40
protected Unit(
Class<? extends U> baseType,
UnaryFunction toBaseConverter,
UnaryFunction fromBaseConverter,
String name,
String symbol) {
Copy link
Member Author

Choose a reason for hiding this comment

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

Should document that subclasses need to define a constructor matching this signature, less the baseType (which should be hardcoded by the subclass). This is required for Units#derive to work

eg

class SomeUnit extends Unit<SomeUnit> {
  SomeUnit(
      UnaryFunction toBaseConverter,
      UnaryFunction fromBaseConverter,
      String name,
      String symbol) {
    super((Class) SomeUnit.class, toBaseConverter, fromBaseConverter, name, symbol);
  }
}

*
* @param magnitude the magnitude of the measure to create
*/
public Measure<U> of(double magnitude) {
Copy link
Member Author

Choose a reason for hiding this comment

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

quantity or qty may be more descriptive, eg Inches.quantity(5) or Seconds.qty(0.020)

wpiunits/src/main/java/edu/wpi/first/units/Measure.java Outdated Show resolved Hide resolved
wpiunits/src/main/java/edu/wpi/first/units/Measure.java Outdated Show resolved Hide resolved

// Time
public static final Time Seconds = BaseUnits.Time;
public static final Time Second = Seconds; // singularized alias
Copy link
Member Author

Choose a reason for hiding this comment

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

These aliases are really nice for making combined units read nicely like Feet.per(Second) instead of Feet.per(Seconds). Would probably be worthwhile making singular aliases for the rest of the unit definitions in this file

public static final Velocity<Angle> DegreesPerSecond = Degrees.per(Second);

// Acceleration
public static final Velocity<Velocity<Distance>> MetersPerSecondPerSecond =
Copy link
Member Author

Choose a reason for hiding this comment

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

I really wish Java had something like typedef so we could just alias Velocity<Velocity<X>> as Acceleration<X> - and, while we're at it, alias Per<X, Time> to Velocity<X>. Too bad.

.named("Fahrenheit")
.symbol("°F")
.make();

Copy link
Member Author

Choose a reason for hiding this comment

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

Force and torque units could be helpful, too

wpiunits/src/main/java/edu/wpi/first/units/Units.java Outdated Show resolved Hide resolved
@calcmogul
Copy link
Member

Here's what we call all the C++ units, for reference: https://github.com/wpilibsuite/allwpilib/tree/main/wpimath/src/main/native/include/units

@SamCarlberg SamCarlberg marked this pull request as ready for review June 6, 2023 23:31
@SamCarlberg SamCarlberg requested a review from a team as a code owner June 6, 2023 23:31
Copy link
Member

Choose a reason for hiding this comment

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

This (and ReadOnlyPrimitiveLong) feel like they should be hoisted to wpiutil, as they're very generic? Although I know that would add a dependency that's not currently present.

@ghost ghost mentioned this pull request Jun 10, 2023
@SamCarlberg
Copy link
Member Author

/format

@PeterJohnson PeterJohnson requested review from a team as code owners June 30, 2023 01:12
@PeterJohnson
Copy link
Member

Checkstyle is failing with two errors:

Error: eckstyle] [ERROR] /__w/allwpilib/allwpilib/wpiunits/src/main/java/edu/wpi/first/units/Measure.java:123:6: Unused @param tag for 'divisor'. [JavadocMethod]
Error: eckstyle] [ERROR] /__w/allwpilib/allwpilib/wpiunits/src/main/java/edu/wpi/first/units/Measure.java:136: Line is longer than 100 characters (found 119). [LineLength]

Currently exists as a standalone project with nothing depending on it
Avoids autoboxing allocations when dealing with combinatory unit caches
Realized LongToObjectMap was fairly complex, left some documentation to describe the workings
Prefer the Unit#of and Unit#ofBaseUnits instead
Tweak equivlance/isNear checks to broaden accepted unit inputs
ElectricPotential -> Voltage
ElectricCurrent -> Current
Docs said it the method converted *to* the new unit, not *from* it
Lets us use unit declarations as `Unit<XYZ>` instead of needing the internal type `XYZ`
Backwards compatible because `U` is declared to extend `Unit<U>`
Change RPM to base on rotation instead of revolution
eg `x.mut_plus(y).mut_divide(z)` for `(x + y) / z` with zero allocations
can still use `x.plus(y).divide(z)` for readability at the cost of extra allocations, which is fine if not used in a hot loop
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants