mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[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));
```
This commit is contained in:
92
wpiunits/src/test/java/edu/wpi/first/units/EncoderTest.java
Normal file
92
wpiunits/src/test/java/edu/wpi/first/units/EncoderTest.java
Normal file
@@ -0,0 +1,92 @@
|
||||
// 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 static edu.wpi.first.units.Units.Inches;
|
||||
import static edu.wpi.first.units.Units.Revolutions;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Value;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class EncoderTest {
|
||||
static class Encoder<U extends Unit<U>> {
|
||||
int m_ticks; // = 0
|
||||
private Measure<U> m_distancePerPulse;
|
||||
private MutableMeasure<U> m_distance;
|
||||
private MutableMeasure<Velocity<U>> m_rate;
|
||||
|
||||
void setDistancePerPulse(Measure<U> distancePerPulse) {
|
||||
m_distancePerPulse = distancePerPulse;
|
||||
m_distance = MutableMeasure.zero(distancePerPulse.unit());
|
||||
m_rate = MutableMeasure.zero(distancePerPulse.unit().per(Second));
|
||||
}
|
||||
|
||||
Measure<U> getDistance() {
|
||||
return m_distance;
|
||||
}
|
||||
|
||||
Measure<Velocity<U>> getRate() {
|
||||
return m_rate;
|
||||
}
|
||||
|
||||
void setTicks(int ticks) {
|
||||
// pretend we read from JNI here instead of being passed a specific value
|
||||
var change = ticks - m_ticks;
|
||||
m_ticks = ticks;
|
||||
m_distance.mut_setMagnitude(m_distancePerPulse.magnitude() * ticks);
|
||||
|
||||
// assumes the last update was 1 second ago - fine for tests
|
||||
m_rate.mut_setMagnitude(m_distancePerPulse.magnitude() * change);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void testAsDistance() {
|
||||
var ticksPerRevolution = Value.of(2048);
|
||||
|
||||
var encoder = new Encoder<Distance>();
|
||||
|
||||
// distance per rotation = (wheel circumference / gear ratio)
|
||||
// distance per tick = distance per rotation / ticks per rotation
|
||||
var wheelDiameter = Inches.of(6);
|
||||
var gearRatio = Value.of(10); // 10:1 ratio
|
||||
Measure<Distance> distancePerPulse =
|
||||
wheelDiameter.times(Math.PI).divide(gearRatio).divide(ticksPerRevolution);
|
||||
encoder.setDistancePerPulse(distancePerPulse);
|
||||
|
||||
encoder.m_ticks = 0;
|
||||
assertEquals(0, encoder.getDistance().in(Inches), Measure.EQUIVALENCE_THRESHOLD);
|
||||
assertEquals(0, encoder.getRate().in(Inches.per(Second)), Measure.EQUIVALENCE_THRESHOLD);
|
||||
|
||||
// one full encoder turn, 1/10th of a wheel rotation
|
||||
encoder.setTicks(2048);
|
||||
assertEquals(6 * Math.PI / 10, encoder.getDistance().in(Inches), Measure.EQUIVALENCE_THRESHOLD);
|
||||
|
||||
// one full encoder turn back, 1/10th of a wheel rotation - rate should be negative
|
||||
encoder.setTicks(0);
|
||||
assertEquals(
|
||||
-6 * Math.PI / 10, encoder.getRate().in(Inches.per(Second)), Measure.EQUIVALENCE_THRESHOLD);
|
||||
}
|
||||
|
||||
@Test
|
||||
void testAsRevolutions() {
|
||||
var ticksPerRevolution = Value.of(2048);
|
||||
|
||||
var encoder = new Encoder<Angle>();
|
||||
|
||||
Measure<Angle> distancePerPulse = Revolutions.of(1).divide(ticksPerRevolution);
|
||||
encoder.setDistancePerPulse(distancePerPulse);
|
||||
|
||||
encoder.m_ticks = 0;
|
||||
assertEquals(0, encoder.getDistance().in(Revolutions), Measure.EQUIVALENCE_THRESHOLD);
|
||||
assertEquals(0, encoder.getRate().in(Revolutions.per(Second)), Measure.EQUIVALENCE_THRESHOLD);
|
||||
|
||||
encoder.setTicks(2048); // one full encoder turn, 1/10th of a wheel rotation
|
||||
assertEquals(1, encoder.getDistance().in(Revolutions), Measure.EQUIVALENCE_THRESHOLD);
|
||||
assertEquals(1, encoder.getRate().in(Revolutions.per(Second)), Measure.EQUIVALENCE_THRESHOLD);
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user