mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
[wpiunits] Java units API rewrite (#6958)
Java generics are too limited to do what we need. This refactors generic code previously in Unit and Measure into unit-specific classes that can have unit-safe math operations (notably, times and divide) that can return values in known units instead of a wildcarded Measure<?>. Unit-specific measure implementations are automatically generated by ./wpiunits/generate_units.py, which generates generic interfaces and mutable and immutable implementations of those interfaces. These make up the bulk of the diff of this PR (approximately 9300 LOC). This also adds units for angular and linear velocities, accelerations, and momenta; moment of inertia; and torque.
This commit is contained in:
@@ -10,12 +10,12 @@ import static edu.wpi.first.units.Units.Microseconds;
|
||||
import static edu.wpi.first.units.Units.Value;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.units.Dimensionless;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.collections.LongToObjectHashMap;
|
||||
import edu.wpi.first.units.measure.Dimensionless;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.units.measure.Frequency;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.util.WPIUtilJNI;
|
||||
import edu.wpi.first.wpilibj.util.Color;
|
||||
import java.util.Map;
|
||||
@@ -99,9 +99,9 @@ public interface LEDPattern {
|
||||
*
|
||||
* <p>This method is intentionally designed to use separate objects for reading and writing data.
|
||||
* By splitting them up, we can easily modify the behavior of some base pattern to make it {@link
|
||||
* #scrollAtRelativeSpeed(Measure) scroll}, {@link #blink(Measure, Measure) blink}, or {@link
|
||||
* #breathe(Measure) breathe} by intercepting the data writes to transform their behavior to
|
||||
* whatever we like.
|
||||
* #scrollAtRelativeSpeed(Frequency) scroll}, {@link #blink(Time, Time) blink}, or {@link
|
||||
* #breathe(Time) breathe} by intercepting the data writes to transform their behavior to whatever
|
||||
* we like.
|
||||
*
|
||||
* @param reader data reader for accessing buffer length and current colors
|
||||
* @param writer data writer for setting new LED colors on the buffer
|
||||
@@ -186,8 +186,8 @@ public interface LEDPattern {
|
||||
* scroll along the length of LEDs and return back to the starting position
|
||||
* @return the scrolling pattern
|
||||
*/
|
||||
default LEDPattern scrollAtRelativeSpeed(Measure<Velocity<Dimensionless>> velocity) {
|
||||
final double periodMicros = 1 / velocity.in(Value.per(Microsecond));
|
||||
default LEDPattern scrollAtRelativeSpeed(Frequency velocity) {
|
||||
final double periodMicros = velocity.asPeriod().in(Microseconds);
|
||||
|
||||
return (reader, writer) -> {
|
||||
int bufLen = reader.getLength();
|
||||
@@ -217,7 +217,7 @@ public interface LEDPattern {
|
||||
*
|
||||
* <pre>
|
||||
* // LEDs per meter, a known value taken from the spec sheet of our particular LED strip
|
||||
* Measure<Distance> LED_SPACING = Meters.of(1.0 / 60);
|
||||
* Distance LED_SPACING = Meters.of(1.0 / 60);
|
||||
*
|
||||
* LEDPattern rainbow = LEDPattern.rainbow();
|
||||
* LEDPattern scrollingRainbow =
|
||||
@@ -232,8 +232,7 @@ public interface LEDPattern {
|
||||
* @param ledSpacing the distance between adjacent LEDs on the physical LED strip
|
||||
* @return the scrolling pattern
|
||||
*/
|
||||
default LEDPattern scrollAtAbsoluteSpeed(
|
||||
Measure<Velocity<Distance>> velocity, Measure<Distance> ledSpacing) {
|
||||
default LEDPattern scrollAtAbsoluteSpeed(LinearVelocity velocity, Distance ledSpacing) {
|
||||
// eg velocity = 10 m/s, spacing = 0.01m
|
||||
// meters per micro = 1e-5 m/us
|
||||
// micros per LED = 1e-2 m / (1e-5 m/us) = 1e-3 us
|
||||
@@ -267,7 +266,7 @@ public interface LEDPattern {
|
||||
* @param offTime how long the pattern should be turned off for, per cycle
|
||||
* @return the blinking pattern
|
||||
*/
|
||||
default LEDPattern blink(Measure<Time> onTime, Measure<Time> offTime) {
|
||||
default LEDPattern blink(Time onTime, Time offTime) {
|
||||
final long totalTimeMicros = (long) (onTime.in(Microseconds) + offTime.in(Microseconds));
|
||||
final long onTimeMicros = (long) onTime.in(Microseconds);
|
||||
|
||||
@@ -281,13 +280,13 @@ public interface LEDPattern {
|
||||
}
|
||||
|
||||
/**
|
||||
* Like {@link #blink(Measure, Measure) blink(onTime, offTime)}, but where the "off" time is
|
||||
* exactly equal to the "on" time.
|
||||
* Like {@link #blink(Time, Time) blink(onTime, offTime)}, but where the "off" time is exactly
|
||||
* equal to the "on" time.
|
||||
*
|
||||
* @param onTime how long the pattern should play for (and be turned off for), per cycle
|
||||
* @return the blinking pattern
|
||||
*/
|
||||
default LEDPattern blink(Measure<Time> onTime) {
|
||||
default LEDPattern blink(Time onTime) {
|
||||
return blink(onTime, onTime);
|
||||
}
|
||||
|
||||
@@ -316,7 +315,7 @@ public interface LEDPattern {
|
||||
* @param period how fast the breathing pattern should complete a single cycle
|
||||
* @return the breathing pattern
|
||||
*/
|
||||
default LEDPattern breathe(Measure<Time> period) {
|
||||
default LEDPattern breathe(Time period) {
|
||||
final long periodMicros = (long) period.in(Microseconds);
|
||||
|
||||
return (reader, writer) -> {
|
||||
@@ -444,7 +443,7 @@ public interface LEDPattern {
|
||||
* @param relativeBrightness the multiplier to apply to all channels to modify brightness
|
||||
* @return the input pattern, displayed at
|
||||
*/
|
||||
default LEDPattern atBrightness(Measure<Dimensionless> relativeBrightness) {
|
||||
default LEDPattern atBrightness(Dimensionless relativeBrightness) {
|
||||
double multiplier = relativeBrightness.in(Value);
|
||||
|
||||
return (reader, writer) -> {
|
||||
|
||||
@@ -11,8 +11,7 @@ import edu.wpi.first.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.hal.NotifierJNI;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import java.util.PriorityQueue;
|
||||
|
||||
/**
|
||||
@@ -199,7 +198,7 @@ public class TimedRobot extends IterativeRobotBase {
|
||||
* @param callback The callback to run.
|
||||
* @param period The period at which to run the callback.
|
||||
*/
|
||||
public final void addPeriodic(Runnable callback, Measure<Time> period) {
|
||||
public final void addPeriodic(Runnable callback, Time period) {
|
||||
addPeriodic(callback, period.in(Seconds));
|
||||
}
|
||||
|
||||
@@ -214,7 +213,7 @@ public class TimedRobot extends IterativeRobotBase {
|
||||
* @param offset The offset from the common starting time. This is useful for scheduling a
|
||||
* callback in a different timeslot relative to TimedRobot.
|
||||
*/
|
||||
public final void addPeriodic(Runnable callback, Measure<Time> period, Measure<Time> offset) {
|
||||
public final void addPeriodic(Runnable callback, Time period, Time offset) {
|
||||
addPeriodic(callback, period.in(Seconds), offset.in(Seconds));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,6 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
|
||||
/** Interface for motor controlling devices. */
|
||||
@@ -24,12 +27,27 @@ public interface MotorController {
|
||||
* <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
|
||||
* properly - unlike the ordinary set function, it is not "set it and forget it."
|
||||
*
|
||||
* @param outputVolts The voltage to output.
|
||||
* @param outputVolts The voltage to output, in Volts.
|
||||
*/
|
||||
default void setVoltage(double outputVolts) {
|
||||
set(outputVolts / RobotController.getBatteryVoltage());
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the voltage output of the MotorController. Compensates for the current bus voltage to
|
||||
* ensure that the desired voltage is output even if the battery voltage is below 12V - highly
|
||||
* useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
|
||||
* calculation).
|
||||
*
|
||||
* <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
|
||||
* properly - unlike the ordinary set function, it is not "set it and forget it."
|
||||
*
|
||||
* @param outputVoltage The voltage to output.
|
||||
*/
|
||||
default void setVoltage(Voltage outputVoltage) {
|
||||
setVoltage(outputVoltage.in(Volts));
|
||||
}
|
||||
|
||||
/**
|
||||
* Common interface for getting the current set speed of a motor controller.
|
||||
*
|
||||
|
||||
@@ -13,10 +13,10 @@ import edu.wpi.first.math.system.LinearSystem;
|
||||
import edu.wpi.first.math.system.plant.DCMotor;
|
||||
import edu.wpi.first.math.system.plant.LinearSystemId;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.AngularAcceleration;
|
||||
import edu.wpi.first.units.measure.AngularVelocity;
|
||||
import edu.wpi.first.units.measure.MutAngularAcceleration;
|
||||
import edu.wpi.first.units.measure.MutAngularVelocity;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
|
||||
/** Represents a simulated flywheel mechanism. */
|
||||
@@ -31,12 +31,10 @@ public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
|
||||
private final double m_jKgMetersSquared;
|
||||
|
||||
// The angular velocity of the system.
|
||||
private final MutableMeasure<Velocity<Angle>> m_angularVelocity =
|
||||
MutableMeasure.zero(RadiansPerSecond);
|
||||
private final MutAngularVelocity m_angularVelocity = RadiansPerSecond.mutable(0);
|
||||
|
||||
// The angular acceleration of the system.
|
||||
private final MutableMeasure<Velocity<Velocity<Angle>>> m_angularAcceleration =
|
||||
MutableMeasure.zero(RadiansPerSecondPerSecond);
|
||||
private final MutAngularAcceleration m_angularAcceleration = RadiansPerSecondPerSecond.mutable(0);
|
||||
|
||||
/**
|
||||
* Creates a simulated flywheel mechanism.
|
||||
@@ -133,7 +131,7 @@ public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
|
||||
*
|
||||
* @return The flywheel's velocity
|
||||
*/
|
||||
public Measure<Velocity<Angle>> getAngularVelocity() {
|
||||
public AngularVelocity getAngularVelocity() {
|
||||
m_angularVelocity.mut_setMagnitude(getAngularVelocityRadPerSec());
|
||||
return m_angularVelocity;
|
||||
}
|
||||
@@ -153,7 +151,7 @@ public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
|
||||
*
|
||||
* @return The flywheel's acceleration.
|
||||
*/
|
||||
public Measure<Velocity<Velocity<Angle>>> getAngularAcceleration() {
|
||||
public AngularAcceleration getAngularAcceleration() {
|
||||
m_angularAcceleration.mut_setMagnitude(getAngularAccelerationRadPerSecSq());
|
||||
return m_angularAcceleration;
|
||||
}
|
||||
|
||||
@@ -12,12 +12,14 @@ import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Current;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.units.measure.Angle;
|
||||
import edu.wpi.first.units.measure.AngularAcceleration;
|
||||
import edu.wpi.first.units.measure.AngularVelocity;
|
||||
import edu.wpi.first.units.measure.Current;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.units.measure.LinearAcceleration;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.util.datalog.DoubleLogEntry;
|
||||
import edu.wpi.first.util.datalog.StringLogEntry;
|
||||
import edu.wpi.first.wpilibj.DataLogManager;
|
||||
@@ -114,7 +116,7 @@ public class SysIdRoutineLog {
|
||||
* @param voltage The voltage to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog voltage(Measure<Voltage> voltage) {
|
||||
public MotorLog voltage(Voltage voltage) {
|
||||
return value("voltage", voltage.in(Volts), Volts.name());
|
||||
}
|
||||
|
||||
@@ -124,7 +126,7 @@ public class SysIdRoutineLog {
|
||||
* @param position The linear position to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog linearPosition(Measure<Distance> position) {
|
||||
public MotorLog linearPosition(Distance position) {
|
||||
return value("position", position.in(Meters), Meters.name());
|
||||
}
|
||||
|
||||
@@ -134,7 +136,7 @@ public class SysIdRoutineLog {
|
||||
* @param position The angular position to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog angularPosition(Measure<Angle> position) {
|
||||
public MotorLog angularPosition(Angle position) {
|
||||
return value("position", position.in(Rotations), Rotations.name());
|
||||
}
|
||||
|
||||
@@ -144,7 +146,7 @@ public class SysIdRoutineLog {
|
||||
* @param velocity The linear velocity to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog linearVelocity(Measure<Velocity<Distance>> velocity) {
|
||||
public MotorLog linearVelocity(LinearVelocity velocity) {
|
||||
return value("velocity", velocity.in(MetersPerSecond), MetersPerSecond.name());
|
||||
}
|
||||
|
||||
@@ -154,7 +156,7 @@ public class SysIdRoutineLog {
|
||||
* @param velocity The angular velocity to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog angularVelocity(Measure<Velocity<Angle>> velocity) {
|
||||
public MotorLog angularVelocity(AngularVelocity velocity) {
|
||||
return value("velocity", velocity.in(RotationsPerSecond), RotationsPerSecond.name());
|
||||
}
|
||||
|
||||
@@ -166,7 +168,7 @@ public class SysIdRoutineLog {
|
||||
* @param acceleration The linear acceleration to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog linearAcceleration(Measure<Velocity<Velocity<Distance>>> acceleration) {
|
||||
public MotorLog linearAcceleration(LinearAcceleration acceleration) {
|
||||
return value(
|
||||
"acceleration",
|
||||
acceleration.in(MetersPerSecond.per(Second)),
|
||||
@@ -181,7 +183,7 @@ public class SysIdRoutineLog {
|
||||
* @param acceleration The angular acceleration to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog angularAcceleration(Measure<Velocity<Velocity<Angle>>> acceleration) {
|
||||
public MotorLog angularAcceleration(AngularAcceleration acceleration) {
|
||||
return value(
|
||||
"acceleration",
|
||||
acceleration.in(RotationsPerSecond.per(Second)),
|
||||
@@ -196,7 +198,7 @@ public class SysIdRoutineLog {
|
||||
* @param current The current to record.
|
||||
* @return The motor log (for call chaining).
|
||||
*/
|
||||
public MotorLog current(Measure<Current> current) {
|
||||
public MotorLog current(Current current) {
|
||||
value("current", current.in(Amps), Amps.name());
|
||||
return this;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user