[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 static org.junit.jupiter.api.Assertions.assertEquals;
|
|
|
|
|
import static org.junit.jupiter.api.Assertions.assertFalse;
|
|
|
|
|
import static org.junit.jupiter.api.Assertions.assertNotSame;
|
|
|
|
|
import static org.junit.jupiter.api.Assertions.assertNull;
|
|
|
|
|
import static org.junit.jupiter.api.Assertions.assertSame;
|
|
|
|
|
import static org.junit.jupiter.api.Assertions.assertTrue;
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
import edu.wpi.first.units.measure.Angle;
|
|
|
|
|
import edu.wpi.first.units.measure.AngularMomentum;
|
|
|
|
|
import edu.wpi.first.units.measure.Distance;
|
|
|
|
|
import edu.wpi.first.units.measure.LinearVelocity;
|
|
|
|
|
import edu.wpi.first.units.measure.Per;
|
|
|
|
|
import edu.wpi.first.units.measure.Time;
|
[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
|
|
|
import org.junit.jupiter.api.Test;
|
|
|
|
|
|
|
|
|
|
class MeasureTest {
|
|
|
|
|
@Test
|
|
|
|
|
void testBasics() {
|
2024-09-07 13:59:29 -04:00
|
|
|
DistanceUnit unit = Units.Feet;
|
[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
|
|
|
double magnitude = 10;
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m = unit.of(magnitude);
|
[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
|
|
|
assertEquals(unit, m.unit(), "Wrong units");
|
|
|
|
|
assertEquals(magnitude, m.magnitude(), 0, "Wrong magnitude");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testMultiply() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m = Units.Feet.of(1);
|
|
|
|
|
Distance m2 = m.times(10);
|
|
|
|
|
assertEquals(10, m2.in(Units.Feet), 1e-12);
|
[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
|
|
|
assertNotSame(m2, m); // make sure state wasn't changed
|
|
|
|
|
}
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
@Test
|
|
|
|
|
void testTimesConversionFactor() {
|
|
|
|
|
Distance m = Units.Feet.of(10);
|
|
|
|
|
|
2024-11-15 13:49:40 -05:00
|
|
|
Per<AngleUnit, DistanceUnit> conversion = Units.Degrees.of(10).div(Units.Feet.of(1));
|
2024-09-07 13:59:29 -04:00
|
|
|
Angle result = m.timesConversionFactor(conversion);
|
|
|
|
|
assertEquals(Units.Degrees.of(100), result);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testTimesConversionFactorComplex() {
|
|
|
|
|
Distance m = Units.Feet.of(1);
|
|
|
|
|
|
|
|
|
|
// Using a complex compound unit here
|
|
|
|
|
// (Per<Mult<Mult<Mass, Per<Distance, Time>>, Distance>, Distance>)
|
|
|
|
|
Per<AngularMomentumUnit, DistanceUnit> conversion =
|
2024-11-15 13:49:40 -05:00
|
|
|
Units.KilogramMetersSquaredPerSecond.of(1).div(Units.Foot.one());
|
2024-09-07 13:59:29 -04:00
|
|
|
|
|
|
|
|
AngularMomentum result = m.timesConversionFactor(conversion);
|
|
|
|
|
assertEquals(Units.KilogramMetersSquaredPerSecond.of(1), result);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testTimesVelocityConversionFactor() {
|
|
|
|
|
Time m = Units.Seconds.of(10);
|
|
|
|
|
|
|
|
|
|
LinearVelocity conversion = Units.MetersPerSecond.of(10);
|
|
|
|
|
Distance result = m.timesConversionFactor(conversion);
|
|
|
|
|
assertEquals(Units.Meters.of(100), result);
|
|
|
|
|
}
|
|
|
|
|
|
[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
|
|
|
@Test
|
|
|
|
|
void testDivide() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m = Units.Meters.of(1);
|
2024-11-15 13:49:40 -05:00
|
|
|
Distance m2 = m.div(10);
|
[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
|
|
|
assertEquals(0.1, m2.magnitude(), 0);
|
|
|
|
|
assertNotSame(m2, m);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testAdd() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m1 = Units.Feet.of(1);
|
|
|
|
|
Distance m2 = Units.Inches.of(2);
|
[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
|
|
|
assertTrue(m1.plus(m2).isEquivalent(Units.Feet.of(1 + 2 / 12d)));
|
|
|
|
|
assertTrue(m2.plus(m1).isEquivalent(Units.Inches.of(14)));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testSubtract() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m1 = Units.Feet.of(1);
|
|
|
|
|
Distance m2 = Units.Inches.of(2);
|
[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
|
|
|
assertTrue(m1.minus(m2).isEquivalent(Units.Feet.of(1 - 2 / 12d)));
|
|
|
|
|
assertTrue(m2.minus(m1).isEquivalent(Units.Inches.of(-10)));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
2024-09-07 13:59:29 -04:00
|
|
|
void testUnaryMinus() {
|
|
|
|
|
Distance m = Units.Feet.of(123);
|
|
|
|
|
Distance negated = m.unaryMinus();
|
|
|
|
|
assertEquals(-123, negated.in(Units.Feet), 1e-12);
|
|
|
|
|
assertEquals(Units.Feet, negated.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
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testEquivalency() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance inches = Units.Inches.of(12);
|
|
|
|
|
Distance feet = Units.Feet.of(1);
|
[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
|
|
|
assertTrue(inches.isEquivalent(feet));
|
|
|
|
|
assertTrue(feet.isEquivalent(inches));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testAs() {
|
2024-09-07 13:59:29 -04:00
|
|
|
Distance m = Units.Inches.of(12);
|
[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
|
|
|
assertEquals(1, m.in(Units.Feet), Measure.EQUIVALENCE_THRESHOLD);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
2023-12-08 13:39:28 -08:00
|
|
|
void testPerMeasureTime() {
|
[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
|
|
|
var measure = Units.Kilograms.of(144);
|
|
|
|
|
var dt = Units.Milliseconds.of(53);
|
|
|
|
|
|
|
|
|
|
// 144 Kg / (53 ms) = (1000 / 53) * 144 Kg/s = (144,000 / 53) Kg/s
|
|
|
|
|
|
2024-11-15 13:49:40 -05:00
|
|
|
var result = measure.div(dt);
|
[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
|
|
|
assertEquals(144_000.0 / 53, result.baseUnitMagnitude(), 1e-5);
|
|
|
|
|
assertEquals(Units.Kilograms.per(Units.Milliseconds), result.unit());
|
|
|
|
|
}
|
|
|
|
|
|
2023-12-08 13:39:28 -08:00
|
|
|
@Test
|
|
|
|
|
void testPerUnitTime() {
|
|
|
|
|
var measure = Units.Kilograms.of(144);
|
|
|
|
|
var result = measure.per(Units.Millisecond);
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
assertEquals(VelocityUnit.class, result.unit().getClass());
|
2023-12-08 13:39:28 -08:00
|
|
|
assertEquals(144_000.0, result.baseUnitMagnitude(), 1e-5);
|
|
|
|
|
assertEquals(Units.Kilograms.per(Units.Milliseconds), result.unit());
|
|
|
|
|
}
|
|
|
|
|
|
2024-05-15 08:22:38 -05:00
|
|
|
@Test
|
|
|
|
|
void testDivideMeasure() {
|
|
|
|
|
// Dimensionless divide
|
|
|
|
|
var m1 = Units.Meters.of(6);
|
|
|
|
|
var m2 = Units.Value.of(3);
|
2024-11-15 13:49:40 -05:00
|
|
|
var result = m1.div(m2);
|
|
|
|
|
assertEquals(2, m1.div(m2).magnitude());
|
2024-09-07 13:59:29 -04:00
|
|
|
assertEquals(Units.Meters, result.unit());
|
2024-05-15 08:22:38 -05:00
|
|
|
// Velocity divide
|
|
|
|
|
var m3 = Units.Meters.of(8);
|
|
|
|
|
var m4 = Units.Meters.per(Units.Second).of(4);
|
2024-11-15 13:49:40 -05:00
|
|
|
var time = m3.div(m4);
|
2024-09-07 13:59:29 -04:00
|
|
|
assertEquals(2, time.magnitude());
|
|
|
|
|
assertEquals(Units.Second, time.unit());
|
|
|
|
|
// PerUnit divide
|
2024-05-15 08:22:38 -05:00
|
|
|
var m5 = Units.Volts.of(6);
|
|
|
|
|
var m6 = Units.Volts.per(Units.Meter).of(2);
|
2024-09-07 13:59:29 -04:00
|
|
|
|
|
|
|
|
// Voltage/(Voltage/Distance) -> Voltage * Distance/Voltage -> Distance
|
2024-11-15 13:49:40 -05:00
|
|
|
var dist = m5.div(m6);
|
2024-09-07 13:59:29 -04:00
|
|
|
assertEquals(3, dist.magnitude());
|
|
|
|
|
assertEquals(Units.Meter, dist.unit());
|
2024-05-15 08:22:38 -05: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));
```
2023-07-23 17:18:17 -04:00
|
|
|
@Test
|
|
|
|
|
void testToShortString() {
|
|
|
|
|
var measure = Units.Volts.of(343);
|
|
|
|
|
assertEquals("3.430e+02 V", measure.toShortString());
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testToLongString() {
|
|
|
|
|
var measure = Units.Volts.of(343);
|
|
|
|
|
assertEquals("343.0 Volt", measure.toLongString());
|
|
|
|
|
assertEquals("343.0001 Volt", Units.Volts.of(343.0001).toLongString());
|
2024-01-20 15:46:38 +11:00
|
|
|
assertEquals("1.2345678912345678E8 Volt", Units.Volts.of(123456789.12345678).toLongString());
|
[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
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testOfBaseUnits() {
|
|
|
|
|
var unit = new ExampleUnit(16);
|
|
|
|
|
var measure = unit.ofBaseUnits(1);
|
|
|
|
|
assertEquals(unit, measure.unit());
|
|
|
|
|
assertEquals(1, measure.baseUnitMagnitude());
|
|
|
|
|
assertEquals(1 / 16.0, measure.magnitude());
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
2023-12-05 00:18:26 -05:00
|
|
|
@SuppressWarnings("SelfComparison")
|
[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
|
|
|
void testCompare() {
|
|
|
|
|
var unit = new ExampleUnit(7);
|
|
|
|
|
var base = unit.of(1);
|
|
|
|
|
var less = unit.of(0.5);
|
|
|
|
|
var more = unit.of(2);
|
|
|
|
|
|
|
|
|
|
assertEquals(0, base.compareTo(base));
|
|
|
|
|
assertEquals(-1, base.compareTo(more));
|
|
|
|
|
assertEquals(1, base.compareTo(less));
|
|
|
|
|
|
|
|
|
|
// lt, lte, gt, gte helper functions
|
|
|
|
|
|
|
|
|
|
assertTrue(base.lt(more));
|
|
|
|
|
assertTrue(base.lte(more));
|
|
|
|
|
assertFalse(base.gt(more));
|
|
|
|
|
assertFalse(base.gte(more));
|
|
|
|
|
|
|
|
|
|
assertTrue(base.gt(less));
|
|
|
|
|
assertTrue(base.gte(less));
|
|
|
|
|
assertFalse(base.lt(less));
|
|
|
|
|
assertFalse(base.lte(less));
|
|
|
|
|
|
|
|
|
|
assertTrue(base.lte(base));
|
|
|
|
|
assertTrue(base.gte(base));
|
|
|
|
|
assertFalse(base.lt(base));
|
|
|
|
|
assertFalse(base.gt(base));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testMinNoArgs() {
|
|
|
|
|
var min = Measure.min();
|
|
|
|
|
assertNull(min);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testMin() {
|
|
|
|
|
var unit = new ExampleUnit(56.1);
|
|
|
|
|
var one = unit.of(1);
|
|
|
|
|
var two = unit.of(2);
|
|
|
|
|
var zero = unit.of(0);
|
|
|
|
|
var veryNegative = unit.of(-12839712);
|
|
|
|
|
|
|
|
|
|
var min = Measure.min(one, two, zero, veryNegative);
|
|
|
|
|
assertSame(veryNegative, min);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testMaxNoArgs() {
|
|
|
|
|
var min = Measure.max();
|
|
|
|
|
assertNull(min);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testMax() {
|
|
|
|
|
var unit = new ExampleUnit(6.551);
|
|
|
|
|
var one = unit.of(1);
|
|
|
|
|
var two = unit.of(2);
|
|
|
|
|
var zero = unit.of(0);
|
|
|
|
|
var veryLarge = unit.of(8217234);
|
|
|
|
|
|
|
|
|
|
var max = Measure.max(one, two, zero, veryLarge);
|
|
|
|
|
assertSame(veryLarge, max);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Test
|
2024-04-22 06:40:33 +03:00
|
|
|
void testIsNearVarianceThreshold() {
|
[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
|
|
|
var unit = new ExampleUnit(92);
|
|
|
|
|
var measureA = unit.of(1.21);
|
|
|
|
|
var measureB = unit.ofBaseUnits(64);
|
|
|
|
|
// A = 1.21 * 92 base units, or 111.32
|
|
|
|
|
// B = 64 base units
|
|
|
|
|
// ratio = 111.32 / 64 = 1.739375 = 173.9375%
|
|
|
|
|
|
|
|
|
|
assertTrue(measureA.isNear(measureA, 0));
|
|
|
|
|
assertTrue(measureB.isNear(measureB, 0));
|
|
|
|
|
|
|
|
|
|
assertFalse(measureA.isNear(measureB, 0));
|
|
|
|
|
assertFalse(measureA.isNear(measureB, 0.50));
|
|
|
|
|
assertFalse(measureA.isNear(measureB, 0.739370));
|
|
|
|
|
assertTrue(measureA.isNear(measureB, 0.739375));
|
|
|
|
|
assertTrue(measureA.isNear(measureB, 100)); // some stupidly large range +/- 10000%
|
2024-01-31 23:18:47 +02:00
|
|
|
|
|
|
|
|
var measureC = unit.of(-1.21);
|
|
|
|
|
var measureD = unit.ofBaseUnits(-64);
|
|
|
|
|
|
|
|
|
|
assertTrue(measureC.isNear(measureC, 0));
|
|
|
|
|
assertTrue(measureD.isNear(measureD, 0));
|
|
|
|
|
|
|
|
|
|
assertFalse(measureC.isNear(measureD, 0));
|
|
|
|
|
assertFalse(measureC.isNear(measureD, 0.50));
|
|
|
|
|
assertFalse(measureC.isNear(measureD, 0.739370));
|
|
|
|
|
assertTrue(measureC.isNear(measureD, 0.739375));
|
|
|
|
|
assertTrue(measureC.isNear(measureD, 100)); // some stupidly large range +/- 10000%
|
|
|
|
|
|
|
|
|
|
var measureE = Units.Meters.of(1);
|
|
|
|
|
var measureF = Units.Feet.of(-3.28084);
|
|
|
|
|
|
|
|
|
|
assertTrue(measureE.isNear(measureF, 2.01));
|
|
|
|
|
assertFalse(measureE.isNear(measureF, 1.99));
|
|
|
|
|
|
|
|
|
|
assertTrue(measureF.isNear(measureE, 2.01));
|
|
|
|
|
assertFalse(measureF.isNear(measureE, 1.99));
|
|
|
|
|
|
|
|
|
|
assertTrue(Units.Feet.zero().isNear(Units.Millimeters.zero(), 0.001));
|
|
|
|
|
assertFalse(Units.Feet.of(2).isNear(Units.Millimeters.of(0), 0.001));
|
[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
|
|
|
}
|
2024-04-22 06:40:33 +03:00
|
|
|
|
|
|
|
|
@Test
|
|
|
|
|
void testIsNearMeasureTolerance() {
|
|
|
|
|
var measureCompared = Units.Meters.of(1);
|
|
|
|
|
var measureComparing = Units.Meters.of(1.2);
|
|
|
|
|
|
|
|
|
|
// Positive value with positive tolerance
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Millimeters.of(300)));
|
|
|
|
|
assertFalse(measureCompared.isNear(measureComparing, Units.Centimeters.of(10)));
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
measureCompared = measureCompared.unaryMinus();
|
|
|
|
|
measureComparing = measureComparing.unaryMinus();
|
2024-04-22 06:40:33 +03:00
|
|
|
|
|
|
|
|
// Negative value with positive tolerance
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Millimeters.of(300)));
|
|
|
|
|
assertFalse(measureCompared.isNear(measureComparing, Units.Centimeters.of(10)));
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
measureCompared = measureCompared.unaryMinus();
|
|
|
|
|
measureComparing = measureComparing.unaryMinus();
|
2024-04-22 06:40:33 +03:00
|
|
|
|
|
|
|
|
// Positive value with negative tolerance
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Millimeters.of(-300)));
|
|
|
|
|
assertFalse(measureCompared.isNear(measureComparing, Units.Centimeters.of(-10)));
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
measureCompared = measureCompared.unaryMinus();
|
|
|
|
|
measureComparing = measureComparing.unaryMinus();
|
2024-04-22 06:40:33 +03:00
|
|
|
|
|
|
|
|
// Negative value with negative tolerance.
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Millimeters.of(-300)));
|
|
|
|
|
assertFalse(measureCompared.isNear(measureComparing, Units.Centimeters.of(-10)));
|
|
|
|
|
|
2024-09-07 13:59:29 -04:00
|
|
|
measureCompared = measureCompared.unaryMinus();
|
|
|
|
|
measureComparing = measureComparing.unaryMinus();
|
2024-04-22 06:40:33 +03:00
|
|
|
|
|
|
|
|
// Tolerance exact difference between measures.
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Millimeters.of(200)));
|
|
|
|
|
assertTrue(measureCompared.isNear(measureComparing, Units.Centimeters.of(-20)));
|
|
|
|
|
}
|
[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
|
|
|
}
|