mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41: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:
2
.github/workflows/pregenerate.yml
vendored
2
.github/workflows/pregenerate.yml
vendored
@@ -32,6 +32,8 @@ jobs:
|
||||
run: ./ntcore/generate_topics.py
|
||||
- name: Run wpimath
|
||||
run: ./wpimath/generate_numbers.py && ./wpimath/generate_quickbuf.py --quickbuf_plugin=protoc-gen-quickbuf-1.3.3-linux-x86_64.exe
|
||||
- name: Run wpiunits
|
||||
run: ./wpiunits/generate_units.py
|
||||
- name: Run HIDs
|
||||
run: ./wpilibj/generate_hids.py && ./wpilibc/generate_hids.py && ./wpilibNewCommands/generate_hids.py
|
||||
- name: Run PWM Controllers
|
||||
|
||||
@@ -203,7 +203,10 @@ task generateJavaDocs(type: Javadoc) {
|
||||
"-edu.wpi.first.math.system.struct," +
|
||||
"-edu.wpi.first.math.system.plant.proto," +
|
||||
"-edu.wpi.first.math.system.plant.struct," +
|
||||
"-edu.wpi.first.math.trajectory.proto", true)
|
||||
"-edu.wpi.first.math.trajectory.proto," +
|
||||
// The .measure package contains generated source files for which automatic javadoc
|
||||
// generation is very difficult to do meaningfully.
|
||||
"-edu.wpi.first.units.measure", true)
|
||||
options.addBooleanOption("Xdoclint:html,missing,reference,syntax", true)
|
||||
options.addBooleanOption('html5', true)
|
||||
options.linkSource(true)
|
||||
|
||||
@@ -9,8 +9,7 @@ import edu.wpi.first.epilogue.logging.NTDataLogger;
|
||||
import edu.wpi.first.epilogue.logging.errors.ErrorHandler;
|
||||
import edu.wpi.first.epilogue.logging.errors.ErrorPrinter;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
|
||||
/**
|
||||
* A configuration object to be used by the generated {@code Epilogue} class to customize its
|
||||
@@ -29,13 +28,13 @@ public class EpilogueConfiguration {
|
||||
* The period Epilogue will log at. By default this is the period that the robot runs at. This is
|
||||
* the field used by bind to configure speed when adding the periodic logging function
|
||||
*/
|
||||
public Measure<Time> loggingPeriod;
|
||||
public Time loggingPeriod;
|
||||
|
||||
/**
|
||||
* The offset from the periodic run that Epilogue will log at. By default this will be half of the
|
||||
* robots period. This is the field used by bind when adding the periodic logging function
|
||||
*/
|
||||
public Measure<Time> loggingPeriodOffset;
|
||||
public Time loggingPeriodOffset;
|
||||
|
||||
/**
|
||||
* The minimum importance level of data to be logged. Defaults to debug, which logs data of all
|
||||
|
||||
@@ -211,7 +211,7 @@ public interface DataLogger {
|
||||
* @param unit the unit to log the measurement in
|
||||
* @param <U> the dimension of the unit
|
||||
*/
|
||||
default <U extends Unit<U>> void log(String identifier, Measure<U> value, U unit) {
|
||||
default <U extends Unit> void log(String identifier, Measure<U> value, U unit) {
|
||||
log(identifier, value.in(unit));
|
||||
}
|
||||
|
||||
|
||||
@@ -14,4 +14,6 @@ suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN"
|
||||
checks="(CustomImportOrder|EmptyLineSeparator|LineLength|JavadocParagraph|MissingJavadocMethod|OverloadMethodsDeclarationOrder|SummaryJavadoc|UnnecessaryParentheses|OperatorWrap|JavadocMethod|JavadocTagContinuationIndentation)" />
|
||||
<suppress files="wpilibj[/\\]src[/\\]generated.*"
|
||||
checks="MethodName" />
|
||||
<!-- Disable checkstyle for generated unit files -->
|
||||
<suppress files="wpiunits[/\\]src[/\\]generated.*" checks=".*"/>
|
||||
</suppressions>
|
||||
|
||||
@@ -4,11 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Seconds;
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.util.function.BooleanConsumer;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
@@ -179,8 +178,8 @@ public abstract class Command implements Sendable {
|
||||
* @param time the timeout duration
|
||||
* @return the command with the timeout added
|
||||
*/
|
||||
public ParallelRaceGroup withTimeout(Measure<Time> time) {
|
||||
return withTimeout(time.in(Second));
|
||||
public ParallelRaceGroup withTimeout(Time time) {
|
||||
return withTimeout(time.in(Seconds));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -6,8 +6,7 @@ package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
|
||||
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import java.util.Map;
|
||||
import java.util.Set;
|
||||
import java.util.function.BooleanSupplier;
|
||||
@@ -137,7 +136,7 @@ public final class Commands {
|
||||
* @return the command
|
||||
* @see WaitCommand
|
||||
*/
|
||||
public static Command waitTime(Measure<Time> time) {
|
||||
public static Command waitTime(Time time) {
|
||||
return new WaitCommand(time);
|
||||
}
|
||||
|
||||
|
||||
@@ -19,9 +19,7 @@ import edu.wpi.first.math.kinematics.MecanumDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.MutLinearVelocity;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import java.util.function.Consumer;
|
||||
import java.util.function.Supplier;
|
||||
@@ -60,22 +58,14 @@ public class MecanumControllerCommand extends Command {
|
||||
private final Supplier<MecanumDriveWheelSpeeds> m_currentWheelSpeeds;
|
||||
private final Consumer<MecanumDriveMotorVoltages> m_outputDriveVoltages;
|
||||
private final Consumer<MecanumDriveWheelSpeeds> m_outputWheelSpeeds;
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevFrontLeftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevRearLeftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevFrontRightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevRearRightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_frontLeftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_rearLeftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_frontRightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_rearRightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutLinearVelocity m_prevFrontLeftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_prevRearLeftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_prevFrontRightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_prevRearRightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_frontLeftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_rearLeftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_frontRightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_rearRightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
|
||||
/**
|
||||
* Constructs a new MecanumControllerCommand that when executed will follow the provided
|
||||
|
||||
@@ -16,9 +16,7 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.math.trajectory.Trajectory;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.MutLinearVelocity;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import java.util.function.BiConsumer;
|
||||
@@ -51,14 +49,10 @@ public class RamseteCommand extends Command {
|
||||
private final PIDController m_rightController;
|
||||
private final BiConsumer<Double, Double> m_output;
|
||||
private DifferentialDriveWheelSpeeds m_prevSpeeds = new DifferentialDriveWheelSpeeds();
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevLeftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_prevRightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_leftSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutableMeasure<Velocity<Distance>> m_rightSpeedSetpoint =
|
||||
MutableMeasure.zero(MetersPerSecond);
|
||||
private final MutLinearVelocity m_prevLeftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_prevRightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_leftSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private final MutLinearVelocity m_rightSpeedSetpoint = MetersPerSecond.mutable(0);
|
||||
private double m_prevTime;
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,10 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Seconds;
|
||||
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
@@ -39,8 +38,8 @@ public class WaitCommand extends Command {
|
||||
*
|
||||
* @param time the time to wait
|
||||
*/
|
||||
public WaitCommand(Measure<Time> time) {
|
||||
this(time.in(Second));
|
||||
public WaitCommand(Time time) {
|
||||
this(time.in(Seconds));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -4,17 +4,16 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command.sysid;
|
||||
|
||||
import static edu.wpi.first.units.MutableMeasure.mutable;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Seconds;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
import static java.util.Map.entry;
|
||||
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import edu.wpi.first.units.Time;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.units.VoltageUnit;
|
||||
import edu.wpi.first.units.measure.MutVoltage;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.units.measure.Velocity;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
@@ -43,7 +42,7 @@ import java.util.function.Consumer;
|
||||
public class SysIdRoutine extends SysIdRoutineLog {
|
||||
private final Config m_config;
|
||||
private final Mechanism m_mechanism;
|
||||
private final MutableMeasure<Voltage> m_outputVolts = mutable(Volts.of(0));
|
||||
private final MutVoltage m_outputVolts = Volts.mutable(0);
|
||||
private final Consumer<State> m_recordState;
|
||||
|
||||
/**
|
||||
@@ -62,13 +61,13 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
/** Hardware-independent configuration for a SysId test routine. */
|
||||
public static class Config {
|
||||
/** The voltage ramp rate used for quasistatic test routines. */
|
||||
public final Measure<Velocity<Voltage>> m_rampRate;
|
||||
public final Velocity<VoltageUnit> m_rampRate;
|
||||
|
||||
/** The step voltage output used for dynamic test routines. */
|
||||
public final Measure<Voltage> m_stepVoltage;
|
||||
public final Voltage m_stepVoltage;
|
||||
|
||||
/** Safety timeout for the test routine commands. */
|
||||
public final Measure<Time> m_timeout;
|
||||
public final Time m_timeout;
|
||||
|
||||
/** Optional handle for recording test state in a third-party logging solution. */
|
||||
public final Consumer<State> m_recordState;
|
||||
@@ -87,11 +86,11 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
* logged in WPILog.
|
||||
*/
|
||||
public Config(
|
||||
Measure<Velocity<Voltage>> rampRate,
|
||||
Measure<Voltage> stepVoltage,
|
||||
Measure<Time> timeout,
|
||||
Velocity<VoltageUnit> rampRate,
|
||||
Voltage stepVoltage,
|
||||
Time timeout,
|
||||
Consumer<State> recordState) {
|
||||
m_rampRate = rampRate != null ? rampRate : Volts.of(1).per(Seconds.of(1));
|
||||
m_rampRate = rampRate != null ? rampRate : Volts.of(1).per(Second);
|
||||
m_stepVoltage = stepVoltage != null ? stepVoltage : Volts.of(7);
|
||||
m_timeout = timeout != null ? timeout : Seconds.of(10);
|
||||
m_recordState = recordState;
|
||||
@@ -107,8 +106,7 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
* @param timeout Safety timeout for the test routine commands. Defaults to 10 seconds if left
|
||||
* null.
|
||||
*/
|
||||
public Config(
|
||||
Measure<Velocity<Voltage>> rampRate, Measure<Voltage> stepVoltage, Measure<Time> timeout) {
|
||||
public Config(Velocity<VoltageUnit> rampRate, Voltage stepVoltage, Time timeout) {
|
||||
this(rampRate, stepVoltage, timeout, null);
|
||||
}
|
||||
|
||||
@@ -132,7 +130,7 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
*/
|
||||
public static class Mechanism {
|
||||
/** Sends the SysId-specified drive signal to the mechanism motors during test routines. */
|
||||
public final Consumer<Measure<Voltage>> m_drive;
|
||||
public final Consumer<? super Voltage> m_drive;
|
||||
|
||||
/**
|
||||
* Returns measured data (voltages, positions, velocities) of the mechanism motors during test
|
||||
@@ -163,10 +161,7 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
* the subsystem if left null.
|
||||
*/
|
||||
public Mechanism(
|
||||
Consumer<Measure<Voltage>> drive,
|
||||
Consumer<SysIdRoutineLog> log,
|
||||
Subsystem subsystem,
|
||||
String name) {
|
||||
Consumer<Voltage> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem, String name) {
|
||||
m_drive = drive;
|
||||
m_log = log != null ? log : l -> {};
|
||||
m_subsystem = subsystem;
|
||||
@@ -189,8 +184,7 @@ public class SysIdRoutine extends SysIdRoutineLog {
|
||||
* will be appended to the log entry title for the routine's test state, e.g.
|
||||
* "sysid-test-state-subsystem".
|
||||
*/
|
||||
public Mechanism(
|
||||
Consumer<Measure<Voltage>> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem) {
|
||||
public Mechanism(Consumer<Voltage> drive, Consumer<SysIdRoutineLog> log, Subsystem subsystem) {
|
||||
this(drive, log, subsystem, null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -14,8 +14,7 @@ import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
@@ -28,7 +27,7 @@ class SysIdRoutineTest {
|
||||
interface Mechanism extends Subsystem {
|
||||
void recordState(SysIdRoutineLog.State state);
|
||||
|
||||
void drive(Measure<Voltage> voltage);
|
||||
void drive(Voltage voltage);
|
||||
|
||||
void log(SysIdRoutineLog log);
|
||||
}
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
@@ -745,7 +745,7 @@ class LEDPatternTest {
|
||||
|
||||
@Test
|
||||
void zeroBrightness() {
|
||||
var pattern = LEDPattern.solid(kRed).atBrightness(Percent.zero());
|
||||
var pattern = LEDPattern.solid(kRed).atBrightness(Percent.of(0));
|
||||
var buffer = new AddressableLEDBuffer(1);
|
||||
pattern.applyTo(buffer);
|
||||
|
||||
|
||||
@@ -7,8 +7,7 @@ package edu.wpi.first.wpilibj.examples.addressableled;
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.wpilibj.AddressableLED;
|
||||
import edu.wpi.first.wpilibj.AddressableLEDBuffer;
|
||||
import edu.wpi.first.wpilibj.LEDPattern;
|
||||
@@ -23,7 +22,7 @@ public class Robot extends TimedRobot {
|
||||
private final LEDPattern m_rainbow = LEDPattern.rainbow(255, 128);
|
||||
|
||||
// Our LED strip has a density of 120 LEDs per meter
|
||||
private static final Measure<Distance> kLedSpacing = Meters.of(1 / 120.0);
|
||||
private static final Distance kLedSpacing = Meters.of(1 / 120.0);
|
||||
|
||||
// Create a new pattern that scrolls the rainbow pattern across the LED strip, moving at a speed
|
||||
// of 1 meter per second.
|
||||
|
||||
@@ -4,16 +4,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.sysid.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.MutableMeasure.mutable;
|
||||
import static edu.wpi.first.units.Units.Meters;
|
||||
import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.units.measure.MutDistance;
|
||||
import edu.wpi.first.units.measure.MutLinearVelocity;
|
||||
import edu.wpi.first.units.measure.MutVoltage;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
@@ -50,11 +47,11 @@ public class Drive extends SubsystemBase {
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
// Mutable holder for unit-safe voltage values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Voltage> m_appliedVoltage = mutable(Volts.of(0));
|
||||
private final MutVoltage m_appliedVoltage = Volts.mutable(0);
|
||||
// Mutable holder for unit-safe linear distance values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Distance> m_distance = mutable(Meters.of(0));
|
||||
private final MutDistance m_distance = Meters.mutable(0);
|
||||
// Mutable holder for unit-safe linear velocity values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Velocity<Distance>> m_velocity = mutable(MetersPerSecond.of(0));
|
||||
private final MutLinearVelocity m_velocity = MetersPerSecond.mutable(0);
|
||||
|
||||
// Create a new SysId routine for characterizing the drive.
|
||||
private final SysIdRoutine m_sysIdRoutine =
|
||||
@@ -63,9 +60,9 @@ public class Drive extends SubsystemBase {
|
||||
new SysIdRoutine.Config(),
|
||||
new SysIdRoutine.Mechanism(
|
||||
// Tell SysId how to plumb the driving voltage to the motors.
|
||||
(Measure<Voltage> volts) -> {
|
||||
m_leftMotor.setVoltage(volts.in(Volts));
|
||||
m_rightMotor.setVoltage(volts.in(Volts));
|
||||
voltage -> {
|
||||
m_leftMotor.setVoltage(voltage);
|
||||
m_rightMotor.setVoltage(voltage);
|
||||
},
|
||||
// Tell SysId how to record a frame of data for each motor on the mechanism being
|
||||
// characterized.
|
||||
|
||||
@@ -4,18 +4,17 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.sysid.subsystems;
|
||||
|
||||
import static edu.wpi.first.units.MutableMeasure.mutable;
|
||||
import static edu.wpi.first.units.Units.Radians;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
import static edu.wpi.first.units.Units.Rotations;
|
||||
import static edu.wpi.first.units.Units.RotationsPerSecond;
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
|
||||
import edu.wpi.first.math.controller.PIDController;
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
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.Voltage;
|
||||
import edu.wpi.first.units.measure.MutAngle;
|
||||
import edu.wpi.first.units.measure.MutAngularVelocity;
|
||||
import edu.wpi.first.units.measure.MutVoltage;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.examples.sysid.Constants.ShooterConstants;
|
||||
@@ -40,11 +39,11 @@ public class Shooter extends SubsystemBase {
|
||||
ShooterConstants.kEncoderReversed);
|
||||
|
||||
// Mutable holder for unit-safe voltage values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Voltage> m_appliedVoltage = mutable(Volts.of(0));
|
||||
private final MutVoltage m_appliedVoltage = Volts.mutable(0);
|
||||
// Mutable holder for unit-safe linear distance values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Angle> m_angle = mutable(Rotations.of(0));
|
||||
private final MutAngle m_angle = Radians.mutable(0);
|
||||
// Mutable holder for unit-safe linear velocity values, persisted to avoid reallocation.
|
||||
private final MutableMeasure<Velocity<Angle>> m_velocity = mutable(RotationsPerSecond.of(0));
|
||||
private final MutAngularVelocity m_velocity = RadiansPerSecond.mutable(0);
|
||||
|
||||
// Create a new SysId routine for characterizing the shooter.
|
||||
private final SysIdRoutine m_sysIdRoutine =
|
||||
@@ -53,9 +52,7 @@ public class Shooter extends SubsystemBase {
|
||||
new SysIdRoutine.Config(),
|
||||
new SysIdRoutine.Mechanism(
|
||||
// Tell SysId how to plumb the driving voltage to the motor(s).
|
||||
(Measure<Voltage> volts) -> {
|
||||
m_shooterMotor.setVoltage(volts.in(Volts));
|
||||
},
|
||||
m_shooterMotor::setVoltage,
|
||||
// Tell SysId how to record a frame of data for each motor on the mechanism being
|
||||
// characterized.
|
||||
log -> {
|
||||
|
||||
@@ -9,9 +9,10 @@ import static edu.wpi.first.units.Units.Volts;
|
||||
import edu.wpi.first.math.controller.proto.SimpleMotorFeedforwardProto;
|
||||
import edu.wpi.first.math.controller.struct.SimpleMotorFeedforwardStruct;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.PerUnit;
|
||||
import edu.wpi.first.units.TimeUnit;
|
||||
import edu.wpi.first.units.Unit;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.Voltage;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
@@ -156,7 +157,7 @@ public class SimpleMotorFeedforward implements ProtobufSerializable, StructSeria
|
||||
* @param setpoint The velocity setpoint.
|
||||
* @return The computed feedforward.
|
||||
*/
|
||||
public <U extends Unit<U>> Measure<Voltage> calculate(Measure<Velocity<U>> setpoint) {
|
||||
public <U extends Unit> Voltage calculate(Measure<? extends PerUnit<U, TimeUnit>> setpoint) {
|
||||
return calculate(setpoint, setpoint);
|
||||
}
|
||||
|
||||
@@ -168,8 +169,9 @@ public class SimpleMotorFeedforward implements ProtobufSerializable, StructSeria
|
||||
* @param nextVelocity The next velocity setpoint.
|
||||
* @return The computed feedforward.
|
||||
*/
|
||||
public <U extends Unit<U>> Measure<Voltage> calculate(
|
||||
Measure<Velocity<U>> currentVelocity, Measure<Velocity<U>> nextVelocity) {
|
||||
public <U extends Unit> Voltage calculate(
|
||||
Measure<? extends PerUnit<U, TimeUnit>> currentVelocity,
|
||||
Measure<? extends PerUnit<U, TimeUnit>> nextVelocity) {
|
||||
if (ka == 0.0) {
|
||||
// Given the following discrete feedforward model
|
||||
//
|
||||
|
||||
@@ -13,8 +13,7 @@ import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import edu.wpi.first.math.geometry.proto.Pose2dProto;
|
||||
import edu.wpi.first.math.geometry.struct.Pose2dStruct;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Collections;
|
||||
@@ -76,7 +75,7 @@ public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, Str
|
||||
* @param y The y component of the translational component of the pose.
|
||||
* @param rotation The rotational component of the pose.
|
||||
*/
|
||||
public Pose2d(Measure<Distance> x, Measure<Distance> y, Rotation2d rotation) {
|
||||
public Pose2d(Distance x, Distance y, Rotation2d rotation) {
|
||||
this(x.in(Meters), y.in(Meters), rotation);
|
||||
}
|
||||
|
||||
|
||||
@@ -16,8 +16,7 @@ import edu.wpi.first.math.geometry.proto.Rotation2dProto;
|
||||
import edu.wpi.first.math.geometry.struct.Rotation2dStruct;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Angle;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -130,7 +129,7 @@ public class Rotation2d
|
||||
*
|
||||
* @param angle The angle of the rotation.
|
||||
*/
|
||||
public Rotation2d(Measure<Angle> angle) {
|
||||
public Rotation2d(Angle angle) {
|
||||
this(angle.in(Radians));
|
||||
}
|
||||
|
||||
@@ -244,7 +243,7 @@ public class Rotation2d
|
||||
*
|
||||
* @return The measure of the Rotation2d.
|
||||
*/
|
||||
public Measure<Angle> getMeasure() {
|
||||
public Angle getMeasure() {
|
||||
return Radians.of(getRadians());
|
||||
}
|
||||
|
||||
|
||||
@@ -8,8 +8,7 @@ import static edu.wpi.first.units.Units.Meters;
|
||||
|
||||
import edu.wpi.first.math.geometry.proto.Transform2dProto;
|
||||
import edu.wpi.first.math.geometry.struct.Transform2dStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -75,7 +74,7 @@ public class Transform2d implements ProtobufSerializable, StructSerializable {
|
||||
* @param y The y component of the translational component of the transform.
|
||||
* @param rotation The rotational component of the transform.
|
||||
*/
|
||||
public Transform2d(Measure<Distance> x, Measure<Distance> y, Rotation2d rotation) {
|
||||
public Transform2d(Distance x, Distance y, Rotation2d rotation) {
|
||||
this(x.in(Meters), y.in(Meters), rotation);
|
||||
}
|
||||
|
||||
|
||||
@@ -17,8 +17,7 @@ import edu.wpi.first.math.geometry.proto.Translation2dProto;
|
||||
import edu.wpi.first.math.geometry.struct.Translation2dStruct;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.numbers.N2;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Collections;
|
||||
@@ -84,7 +83,7 @@ public class Translation2d
|
||||
* @param x The x component of the translation.
|
||||
* @param y The y component of the translation.
|
||||
*/
|
||||
public Translation2d(Measure<Distance> x, Measure<Distance> y) {
|
||||
public Translation2d(Distance x, Distance y) {
|
||||
this(x.in(Meters), y.in(Meters));
|
||||
}
|
||||
|
||||
|
||||
@@ -17,8 +17,7 @@ import edu.wpi.first.math.geometry.proto.Translation3dProto;
|
||||
import edu.wpi.first.math.geometry.struct.Translation3dStruct;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.numbers.N3;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -89,7 +88,7 @@ public class Translation3d
|
||||
* @param y The y component of the translation.
|
||||
* @param z The z component of the translation.
|
||||
*/
|
||||
public Translation3d(Measure<Distance> x, Measure<Distance> y, Measure<Distance> z) {
|
||||
public Translation3d(Distance x, Distance y, Distance z) {
|
||||
this(x.in(Meters), y.in(Meters), z.in(Meters));
|
||||
}
|
||||
|
||||
|
||||
@@ -14,11 +14,9 @@ import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.ChassisSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.ChassisSpeedsStruct;
|
||||
import edu.wpi.first.units.Angle;
|
||||
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.measure.AngularVelocity;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.units.measure.Time;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -72,10 +70,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @param vy Sideways velocity.
|
||||
* @param omega Angular velocity.
|
||||
*/
|
||||
public ChassisSpeeds(
|
||||
Measure<Velocity<Distance>> vx,
|
||||
Measure<Velocity<Distance>> vy,
|
||||
Measure<Velocity<Angle>> omega) {
|
||||
public ChassisSpeeds(LinearVelocity vx, LinearVelocity vy, AngularVelocity omega) {
|
||||
this(vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond));
|
||||
}
|
||||
|
||||
@@ -148,10 +143,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @return Discretized ChassisSpeeds.
|
||||
*/
|
||||
public static ChassisSpeeds discretize(
|
||||
Measure<Velocity<Distance>> vx,
|
||||
Measure<Velocity<Distance>> vy,
|
||||
Measure<Velocity<Angle>> omega,
|
||||
Measure<Time> dt) {
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Time dt) {
|
||||
return discretize(
|
||||
vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), dt.in(Seconds));
|
||||
}
|
||||
@@ -219,10 +211,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @return ChassisSpeeds object representing the speeds in the robot's frame of reference.
|
||||
*/
|
||||
public static ChassisSpeeds fromFieldRelativeSpeeds(
|
||||
Measure<Velocity<Distance>> vx,
|
||||
Measure<Velocity<Distance>> vy,
|
||||
Measure<Velocity<Angle>> omega,
|
||||
Rotation2d robotAngle) {
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) {
|
||||
return fromFieldRelativeSpeeds(
|
||||
vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), robotAngle);
|
||||
}
|
||||
@@ -287,10 +276,7 @@ public class ChassisSpeeds implements ProtobufSerializable, StructSerializable {
|
||||
* @return ChassisSpeeds object representing the speeds in the field's frame of reference.
|
||||
*/
|
||||
public static ChassisSpeeds fromRobotRelativeSpeeds(
|
||||
Measure<Velocity<Distance>> vx,
|
||||
Measure<Velocity<Distance>> vy,
|
||||
Measure<Velocity<Angle>> omega,
|
||||
Rotation2d robotAngle) {
|
||||
LinearVelocity vx, LinearVelocity vy, AngularVelocity omega, Rotation2d robotAngle) {
|
||||
return fromRobotRelativeSpeeds(
|
||||
vx.in(MetersPerSecond), vy.in(MetersPerSecond), omega.in(RadiansPerSecond), robotAngle);
|
||||
}
|
||||
|
||||
@@ -11,8 +11,7 @@ import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.DifferentialDriveKinematicsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.DifferentialDriveKinematicsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
@@ -58,7 +57,7 @@ public class DifferentialDriveKinematics
|
||||
* between the left wheels and right wheels. However, the empirical value may be larger than
|
||||
* the physical measured value due to scrubbing effects.
|
||||
*/
|
||||
public DifferentialDriveKinematics(Measure<Distance> trackWidth) {
|
||||
public DifferentialDriveKinematics(Distance trackWidth) {
|
||||
this(trackWidth.in(Meters));
|
||||
}
|
||||
|
||||
|
||||
@@ -10,8 +10,7 @@ import edu.wpi.first.math.MathSharedStore;
|
||||
import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
|
||||
/**
|
||||
* Class for differential drive odometry. Odometry allows you to track the robot's position on the
|
||||
@@ -55,8 +54,8 @@ public class DifferentialDriveOdometry extends Odometry<DifferentialDriveWheelPo
|
||||
*/
|
||||
public DifferentialDriveOdometry(
|
||||
Rotation2d gyroAngle,
|
||||
Measure<Distance> leftDistance,
|
||||
Measure<Distance> rightDistance,
|
||||
Distance leftDistance,
|
||||
Distance rightDistance,
|
||||
Pose2d initialPoseMeters) {
|
||||
this(gyroAngle, leftDistance.in(Meters), rightDistance.in(Meters), initialPoseMeters);
|
||||
}
|
||||
@@ -81,7 +80,7 @@ public class DifferentialDriveOdometry extends Odometry<DifferentialDriveWheelPo
|
||||
* @param rightDistance The distance traveled by the right encoder.
|
||||
*/
|
||||
public DifferentialDriveOdometry(
|
||||
Rotation2d gyroAngle, Measure<Distance> leftDistance, Measure<Distance> rightDistance) {
|
||||
Rotation2d gyroAngle, Distance leftDistance, Distance rightDistance) {
|
||||
this(gyroAngle, leftDistance, rightDistance, Pose2d.kZero);
|
||||
}
|
||||
|
||||
@@ -119,10 +118,7 @@ public class DifferentialDriveOdometry extends Odometry<DifferentialDriveWheelPo
|
||||
* @param poseMeters The position on the field that your robot is at.
|
||||
*/
|
||||
public void resetPosition(
|
||||
Rotation2d gyroAngle,
|
||||
Measure<Distance> leftDistance,
|
||||
Measure<Distance> rightDistance,
|
||||
Pose2d poseMeters) {
|
||||
Rotation2d gyroAngle, Distance leftDistance, Distance rightDistance, Pose2d poseMeters) {
|
||||
resetPosition(gyroAngle, leftDistance.in(Meters), rightDistance.in(Meters), poseMeters);
|
||||
}
|
||||
|
||||
|
||||
@@ -10,8 +10,7 @@ import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.kinematics.proto.DifferentialDriveWheelPositionsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.DifferentialDriveWheelPositionsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import java.util.Objects;
|
||||
|
||||
/** Represents the wheel positions for a differential drive drivetrain. */
|
||||
@@ -48,7 +47,7 @@ public class DifferentialDriveWheelPositions
|
||||
* @param left Distance measured by the left side.
|
||||
* @param right Distance measured by the right side.
|
||||
*/
|
||||
public DifferentialDriveWheelPositions(Measure<Distance> left, Measure<Distance> right) {
|
||||
public DifferentialDriveWheelPositions(Distance left, Distance right) {
|
||||
this(left.in(Meters), right.in(Meters));
|
||||
}
|
||||
|
||||
|
||||
@@ -8,9 +8,7 @@ import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.math.kinematics.proto.DifferentialDriveWheelSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.DifferentialDriveWheelSpeedsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
@@ -50,8 +48,7 @@ public class DifferentialDriveWheelSpeeds implements ProtobufSerializable, Struc
|
||||
* @param left The left speed.
|
||||
* @param right The right speed.
|
||||
*/
|
||||
public DifferentialDriveWheelSpeeds(
|
||||
Measure<Velocity<Distance>> left, Measure<Velocity<Distance>> right) {
|
||||
public DifferentialDriveWheelSpeeds(LinearVelocity left, LinearVelocity right) {
|
||||
this(left.in(MetersPerSecond), right.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
@@ -85,7 +82,7 @@ public class DifferentialDriveWheelSpeeds implements ProtobufSerializable, Struc
|
||||
*
|
||||
* @param attainableMaxSpeed The absolute max speed that a wheel can reach.
|
||||
*/
|
||||
public void desaturate(Measure<Velocity<Distance>> attainableMaxSpeed) {
|
||||
public void desaturate(LinearVelocity attainableMaxSpeed) {
|
||||
desaturate(attainableMaxSpeed.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
|
||||
@@ -10,8 +10,7 @@ import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.kinematics.proto.MecanumDriveWheelPositionsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelPositionsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -71,10 +70,7 @@ public class MecanumDriveWheelPositions
|
||||
* @param rearRight Distance measured by the rear right wheel.
|
||||
*/
|
||||
public MecanumDriveWheelPositions(
|
||||
Measure<Distance> frontLeft,
|
||||
Measure<Distance> frontRight,
|
||||
Measure<Distance> rearLeft,
|
||||
Measure<Distance> rearRight) {
|
||||
Distance frontLeft, Distance frontRight, Distance rearLeft, Distance rearRight) {
|
||||
this(frontLeft.in(Meters), frontRight.in(Meters), rearLeft.in(Meters), rearRight.in(Meters));
|
||||
}
|
||||
|
||||
|
||||
@@ -8,9 +8,7 @@ import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
|
||||
import edu.wpi.first.math.kinematics.proto.MecanumDriveWheelSpeedsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.MecanumDriveWheelSpeedsStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
|
||||
@@ -65,10 +63,10 @@ public class MecanumDriveWheelSpeeds implements ProtobufSerializable, StructSeri
|
||||
* @param rearRight Speed of the rear right wheel.
|
||||
*/
|
||||
public MecanumDriveWheelSpeeds(
|
||||
Measure<Velocity<Distance>> frontLeft,
|
||||
Measure<Velocity<Distance>> frontRight,
|
||||
Measure<Velocity<Distance>> rearLeft,
|
||||
Measure<Velocity<Distance>> rearRight) {
|
||||
LinearVelocity frontLeft,
|
||||
LinearVelocity frontRight,
|
||||
LinearVelocity rearLeft,
|
||||
LinearVelocity rearRight) {
|
||||
this(
|
||||
frontLeft.in(MetersPerSecond),
|
||||
frontRight.in(MetersPerSecond),
|
||||
@@ -114,7 +112,7 @@ public class MecanumDriveWheelSpeeds implements ProtobufSerializable, StructSeri
|
||||
*
|
||||
* @param attainableMaxSpeed The absolute max speed that a wheel can reach.
|
||||
*/
|
||||
public void desaturate(Measure<Velocity<Distance>> attainableMaxSpeed) {
|
||||
public void desaturate(LinearVelocity attainableMaxSpeed) {
|
||||
desaturate(attainableMaxSpeed.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
|
||||
@@ -14,10 +14,8 @@ import edu.wpi.first.math.geometry.Translation2d;
|
||||
import edu.wpi.first.math.geometry.Twist2d;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveDriveKinematicsProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveDriveKinematicsStruct;
|
||||
import edu.wpi.first.units.Angle;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.AngularVelocity;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.Struct;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
@@ -307,7 +305,7 @@ public class SwerveDriveKinematics
|
||||
* @param attainableMaxSpeed The absolute max speed that a module can reach.
|
||||
*/
|
||||
public static void desaturateWheelSpeeds(
|
||||
SwerveModuleState[] moduleStates, Measure<Velocity<Distance>> attainableMaxSpeed) {
|
||||
SwerveModuleState[] moduleStates, LinearVelocity attainableMaxSpeed) {
|
||||
desaturateWheelSpeeds(moduleStates, attainableMaxSpeed.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
@@ -379,9 +377,9 @@ public class SwerveDriveKinematics
|
||||
public static void desaturateWheelSpeeds(
|
||||
SwerveModuleState[] moduleStates,
|
||||
ChassisSpeeds desiredChassisSpeed,
|
||||
Measure<Velocity<Distance>> attainableMaxModuleSpeed,
|
||||
Measure<Velocity<Distance>> attainableMaxTranslationalSpeed,
|
||||
Measure<Velocity<Angle>> attainableMaxRotationalVelocity) {
|
||||
LinearVelocity attainableMaxModuleSpeed,
|
||||
LinearVelocity attainableMaxTranslationalSpeed,
|
||||
AngularVelocity attainableMaxRotationalVelocity) {
|
||||
desaturateWheelSpeeds(
|
||||
moduleStates,
|
||||
desiredChassisSpeed,
|
||||
|
||||
@@ -11,8 +11,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.interpolation.Interpolatable;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveModulePositionProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveModulePositionStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.measure.Distance;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -55,7 +54,7 @@ public class SwerveModulePosition
|
||||
* @param distance The distance measured by the wheel of the module.
|
||||
* @param angle The angle of the module.
|
||||
*/
|
||||
public SwerveModulePosition(Measure<Distance> distance, Rotation2d angle) {
|
||||
public SwerveModulePosition(Distance distance, Rotation2d angle) {
|
||||
this(distance.in(Meters), angle);
|
||||
}
|
||||
|
||||
|
||||
@@ -9,9 +9,7 @@ import static edu.wpi.first.units.Units.MetersPerSecond;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.kinematics.proto.SwerveModuleStateProto;
|
||||
import edu.wpi.first.math.kinematics.struct.SwerveModuleStateStruct;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import edu.wpi.first.util.protobuf.ProtobufSerializable;
|
||||
import edu.wpi.first.util.struct.StructSerializable;
|
||||
import java.util.Objects;
|
||||
@@ -51,7 +49,7 @@ public class SwerveModuleState
|
||||
* @param speed The speed of the wheel of the module.
|
||||
* @param angle The angle of the module.
|
||||
*/
|
||||
public SwerveModuleState(Measure<Velocity<Distance>> speed, Rotation2d angle) {
|
||||
public SwerveModuleState(LinearVelocity speed, Rotation2d angle) {
|
||||
this(speed.in(MetersPerSecond), angle);
|
||||
}
|
||||
|
||||
|
||||
@@ -14,9 +14,8 @@ import edu.wpi.first.math.trajectory.constraint.DifferentialDriveKinematicsConst
|
||||
import edu.wpi.first.math.trajectory.constraint.MecanumDriveKinematicsConstraint;
|
||||
import edu.wpi.first.math.trajectory.constraint.SwerveDriveKinematicsConstraint;
|
||||
import edu.wpi.first.math.trajectory.constraint.TrajectoryConstraint;
|
||||
import edu.wpi.first.units.Distance;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import edu.wpi.first.units.measure.LinearAcceleration;
|
||||
import edu.wpi.first.units.measure.LinearVelocity;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
@@ -55,9 +54,7 @@ public class TrajectoryConfig {
|
||||
* @param maxVelocity The max velocity for the trajectory.
|
||||
* @param maxAcceleration The max acceleration for the trajectory.
|
||||
*/
|
||||
public TrajectoryConfig(
|
||||
Measure<Velocity<Distance>> maxVelocity,
|
||||
Measure<Velocity<Velocity<Distance>>> maxAcceleration) {
|
||||
public TrajectoryConfig(LinearVelocity maxVelocity, LinearAcceleration maxAcceleration) {
|
||||
this(maxVelocity.in(MetersPerSecond), maxAcceleration.in(MetersPerSecondPerSecond));
|
||||
}
|
||||
|
||||
@@ -145,7 +142,7 @@ public class TrajectoryConfig {
|
||||
* @param startVelocity The start velocity of the trajectory.
|
||||
* @return Instance of the current config object.
|
||||
*/
|
||||
public TrajectoryConfig setStartVelocity(Measure<Velocity<Distance>> startVelocity) {
|
||||
public TrajectoryConfig setStartVelocity(LinearVelocity startVelocity) {
|
||||
return setStartVelocity(startVelocity.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
@@ -175,7 +172,7 @@ public class TrajectoryConfig {
|
||||
* @param endVelocity The end velocity of the trajectory.
|
||||
* @return Instance of the current config object.
|
||||
*/
|
||||
public TrajectoryConfig setEndVelocity(Measure<Velocity<Distance>> endVelocity) {
|
||||
public TrajectoryConfig setEndVelocity(LinearVelocity endVelocity) {
|
||||
return setEndVelocity(endVelocity.in(MetersPerSecond));
|
||||
}
|
||||
|
||||
|
||||
@@ -7,8 +7,9 @@ package edu.wpi.first.math.trajectory;
|
||||
import edu.wpi.first.math.MathSharedStore;
|
||||
import edu.wpi.first.math.MathUsageId;
|
||||
import edu.wpi.first.units.Measure;
|
||||
import edu.wpi.first.units.PerUnit;
|
||||
import edu.wpi.first.units.TimeUnit;
|
||||
import edu.wpi.first.units.Unit;
|
||||
import edu.wpi.first.units.Velocity;
|
||||
import java.util.Objects;
|
||||
|
||||
/**
|
||||
@@ -79,8 +80,10 @@ public class TrapezoidProfile {
|
||||
* @param maxVelocity maximum velocity
|
||||
* @param maxAcceleration maximum acceleration
|
||||
*/
|
||||
public <U extends Unit<U>> Constraints(
|
||||
Measure<Velocity<U>> maxVelocity, Measure<Velocity<Velocity<U>>> maxAcceleration) {
|
||||
public <U extends Unit> Constraints(
|
||||
Measure<? extends PerUnit<? extends U, TimeUnit>> maxVelocity,
|
||||
Measure<? extends PerUnit<? extends PerUnit<? extends U, TimeUnit>, TimeUnit>>
|
||||
maxAcceleration) {
|
||||
this(maxVelocity.baseUnitMagnitude(), maxAcceleration.baseUnitMagnitude());
|
||||
}
|
||||
}
|
||||
@@ -114,7 +117,8 @@ public class TrapezoidProfile {
|
||||
* @param position The position at this state.
|
||||
* @param velocity The velocity at this state.
|
||||
*/
|
||||
public <U extends Unit<U>> State(Measure<U> position, Measure<Velocity<U>> velocity) {
|
||||
public <U extends Unit> State(
|
||||
Measure<U> position, Measure<? extends PerUnit<? extends U, TimeUnit>> velocity) {
|
||||
this(position.baseUnitMagnitude(), velocity.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@@ -13,7 +13,6 @@ import edu.wpi.first.math.MatBuilder;
|
||||
import edu.wpi.first.math.Nat;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.numbers.N1;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class SimpleMotorFeedforwardTest {
|
||||
@@ -32,8 +31,8 @@ class SimpleMotorFeedforwardTest {
|
||||
|
||||
var r = VecBuilder.fill(2.0);
|
||||
var nextR = VecBuilder.fill(3.0);
|
||||
var currentVelocity = MutableMeasure.ofBaseUnits(2.0, RadiansPerSecond);
|
||||
var nextVelocity = MutableMeasure.ofBaseUnits(3.0, RadiansPerSecond);
|
||||
var currentVelocity = RadiansPerSecond.mutable(2.0);
|
||||
var nextVelocity = RadiansPerSecond.mutable(3.0);
|
||||
|
||||
assertEquals(
|
||||
37.52499583432516 + 0.5,
|
||||
|
||||
@@ -49,7 +49,7 @@ class ChassisSpeedsTest {
|
||||
@Test
|
||||
void testMeasureConstructor() {
|
||||
var vx = InchesPerSecond.of(14.52);
|
||||
var vy = InchesPerSecond.zero();
|
||||
var vy = InchesPerSecond.of(0);
|
||||
var omega = RPM.of(0.02);
|
||||
var speeds = new ChassisSpeeds(vx, vy, omega);
|
||||
|
||||
|
||||
@@ -11,7 +11,6 @@ import static org.junit.jupiter.api.Assertions.assertNotEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.units.MutableMeasure;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
@@ -45,8 +44,8 @@ class ExponentialProfileTest {
|
||||
private static ExponentialProfile.State checkDynamics(
|
||||
ExponentialProfile profile, ExponentialProfile.State current, ExponentialProfile.State goal) {
|
||||
var next = profile.calculate(kDt, current, goal);
|
||||
var currentVelocity = MutableMeasure.ofBaseUnits(current.velocity, RadiansPerSecond);
|
||||
var nextVelocity = MutableMeasure.ofBaseUnits(next.velocity, RadiansPerSecond);
|
||||
var currentVelocity = RadiansPerSecond.mutable(current.velocity);
|
||||
var nextVelocity = RadiansPerSecond.mutable(next.velocity);
|
||||
var signal = feedforward.calculate(currentVelocity, nextVelocity);
|
||||
|
||||
assertTrue(Math.abs(signal.magnitude()) < constraints.maxInput + 1e-9);
|
||||
|
||||
@@ -4,7 +4,7 @@ project(wpiunits)
|
||||
if(WITH_JAVA)
|
||||
include(UseJava)
|
||||
|
||||
file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
|
||||
file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java)
|
||||
|
||||
add_jar(
|
||||
wpiunits_jar
|
||||
@@ -24,7 +24,9 @@ if(WITH_JAVA_SOURCE)
|
||||
include(CreateSourceJar)
|
||||
add_source_jar(
|
||||
wpiunits_src_jar
|
||||
BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java
|
||||
BASE_DIRECTORIES
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/src/main/java
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java
|
||||
OUTPUT_NAME wpiunits-sources
|
||||
)
|
||||
set_property(TARGET wpiunits_src_jar PROPERTY FOLDER "java")
|
||||
|
||||
@@ -12,3 +12,5 @@ apply from: "${rootDir}/shared/java/javacommon.gradle"
|
||||
|
||||
dependencies {
|
||||
}
|
||||
|
||||
sourceSets.main.java.srcDir "${projectDir}/src/generated/main/java"
|
||||
|
||||
362
wpiunits/generate_units.py
Executable file
362
wpiunits/generate_units.py
Executable file
@@ -0,0 +1,362 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
# 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.
|
||||
|
||||
# This script generates unit-specific interfaces and mutable and immutable implementations of
|
||||
# those interfaces.
|
||||
# Generated files will be located in wpiunits/src/generated/main/
|
||||
|
||||
import inspect
|
||||
import os
|
||||
import re
|
||||
from jinja2 import Environment, FileSystemLoader
|
||||
|
||||
|
||||
def output(outPath, outfn, contents):
|
||||
if not os.path.exists(outPath):
|
||||
os.makedirs(outPath)
|
||||
|
||||
outpathname = f"{outPath}/{outfn}"
|
||||
|
||||
if os.path.exists(outpathname):
|
||||
with open(outpathname, "r") as f:
|
||||
if f.read() == contents:
|
||||
return
|
||||
|
||||
# File either doesn't exist or has different contents
|
||||
with open(outpathname, "w", newline="\n") as f:
|
||||
f.write(contents)
|
||||
|
||||
|
||||
# The units for which multiply and divide mathematical operations are defined
|
||||
MATH_OPERATION_UNITS = [
|
||||
"Acceleration<?>",
|
||||
"Angle",
|
||||
"AngularAcceleration",
|
||||
"AngularMomentum",
|
||||
"AngularVelocity",
|
||||
"Current",
|
||||
"Dimensionless",
|
||||
"Distance",
|
||||
"Energy",
|
||||
"Force",
|
||||
"Frequency",
|
||||
"LinearAcceleration",
|
||||
"LinearMomentum",
|
||||
"LinearVelocity",
|
||||
"Mass",
|
||||
"MomentOfInertia",
|
||||
"Mult<?, ?>",
|
||||
"Per<?, ?>",
|
||||
"Power",
|
||||
"Temperature",
|
||||
"Time",
|
||||
"Torque",
|
||||
"Velocity<?>",
|
||||
"Voltage",
|
||||
]
|
||||
|
||||
# Configurations for all generated units
|
||||
UNIT_CONFIGURATIONS = {
|
||||
"Acceleration": {
|
||||
"base_unit": "unit()",
|
||||
"generics": {"D": {"extends": "Unit"}},
|
||||
"multiply": {},
|
||||
"divide": {},
|
||||
},
|
||||
"Angle": {
|
||||
"base_unit": "Radians",
|
||||
"multiply": {"Frequency": "AngularVelocity"},
|
||||
"divide": {"Time": "AngularVelocity"},
|
||||
},
|
||||
"AngularAcceleration": {
|
||||
"base_unit": "RadiansPerSecondPerSecond",
|
||||
"multiply": {"Time": "AngularVelocity"},
|
||||
"divide": {"Frequency": "AngularVelocity"},
|
||||
},
|
||||
"AngularMomentum": {
|
||||
"base_unit": "KilogramMetersSquaredPerSecond",
|
||||
"multiply": {},
|
||||
"divide": {"AngularVelocity": "MomentOfInertia"},
|
||||
},
|
||||
"AngularVelocity": {
|
||||
"base_unit": "RadiansPerSecond",
|
||||
"multiply": {"Time": "Angle", "Frequency": "AngularAcceleration"},
|
||||
"divide": {"Time": "AngularAcceleration"},
|
||||
"extra": inspect.cleandoc(
|
||||
"""
|
||||
default Frequency asFrequency() { return Hertz.of(baseUnitMagnitude()); }
|
||||
"""
|
||||
),
|
||||
},
|
||||
"Current": {"base_unit": "Amps", "multiply": {"Voltage": "Power"}, "divide": {}},
|
||||
"Dimensionless": {
|
||||
"base_unit": "Value",
|
||||
"multiply": {
|
||||
"Angle": "Angle",
|
||||
"AngularAcceleration": "AngularAcceleration",
|
||||
"AngularMomentum": "AngularMomentum",
|
||||
"AngularVelocity": "AngularVelocity",
|
||||
"Current": "Current",
|
||||
"Dimensionless": "Dimensionless",
|
||||
"Distance": "Distance",
|
||||
"Energy": "Energy",
|
||||
"Force": "Force",
|
||||
"Frequency": "Frequency",
|
||||
"LinearAcceleration": "LinearAcceleration",
|
||||
"LinearMomentum": "LinearMomentum",
|
||||
"LinearVelocity": "LinearVelocity",
|
||||
"Mass": "Mass",
|
||||
"MomentOfInertia": "MomentOfInertia",
|
||||
"Power": "Power",
|
||||
"Temperature": "Temperature",
|
||||
"Time": "Time",
|
||||
"Torque": "Torque",
|
||||
"Voltage": "Voltage",
|
||||
},
|
||||
"divide": {
|
||||
"Time": "Frequency",
|
||||
# TODO:
|
||||
# "AngularVelocity": "Per<TimeUnit, AngleUnit>",
|
||||
# "AngularAcceleration": "Per<TimeUnit, AngularVelocityUnit>",
|
||||
# "LinearVelocity": "Per<TimeUnit, DistanceUnit>",
|
||||
# "LinearAcceleration": "Per<TimeUnit, LinearVelocityUnit>",
|
||||
# "Velocity<?>": "Per<TimeUnit, ?>",
|
||||
# "Acceleration<?>": "Per<TimeUnit, VelocityUnit<?>>
|
||||
# "Per<N, D>": "Per<D, N>"
|
||||
},
|
||||
},
|
||||
"Distance": {
|
||||
"base_unit": "Meters",
|
||||
"multiply": {
|
||||
"Frequency": "LinearVelocity",
|
||||
# Distance x Force = Torque
|
||||
# Force x Distance = Energy
|
||||
"Force": "Torque",
|
||||
},
|
||||
"divide": {"Time": "LinearVelocity", "LinearVelocity": "Time"},
|
||||
},
|
||||
"Energy": {
|
||||
"base_unit": "Joules",
|
||||
"multiply": {"Frequency": "Power"},
|
||||
"divide": {"Time": "Power"},
|
||||
},
|
||||
"Force": {
|
||||
"base_unit": "Newtons",
|
||||
"multiply": {
|
||||
# Distance x Force = Torque
|
||||
# Force x Distance = Energy
|
||||
"Distance": "Energy"
|
||||
},
|
||||
"divide": {"Mass": "LinearAcceleration", "LinearAcceleration": "Mass"},
|
||||
},
|
||||
"Frequency": {
|
||||
"base_unit": "Hertz",
|
||||
"multiply": {
|
||||
"Time": "Dimensionless",
|
||||
"Distance": "LinearVelocity",
|
||||
"LinearVelocity": "LinearAcceleration",
|
||||
"Angle": "AngularVelocity",
|
||||
"AngularVelocity": "AngularAcceleration",
|
||||
},
|
||||
"divide": {},
|
||||
"extra": inspect.cleandoc(
|
||||
"""
|
||||
/** Converts this frequency to the time period between cycles. */
|
||||
default Time asPeriod() { return Seconds.of(1 / baseUnitMagnitude()); }
|
||||
"""
|
||||
),
|
||||
},
|
||||
"LinearAcceleration": {
|
||||
"base_unit": "MetersPerSecondPerSecond",
|
||||
"multiply": {"Time": "LinearVelocity"},
|
||||
"divide": {"Frequency": "LinearVelocity"},
|
||||
},
|
||||
"LinearMomentum": {
|
||||
"base_unit": "KilogramMetersPerSecond",
|
||||
"multiply": {"Frequency": "Force"},
|
||||
"divide": {"Mass": "LinearVelocity", "LinearVelocity": "Mass", "Time": "Force"},
|
||||
},
|
||||
"LinearVelocity": {
|
||||
"base_unit": "MetersPerSecond",
|
||||
"multiply": {"Time": "Distance", "Frequency": "LinearAcceleration"},
|
||||
"divide": {"Time": "LinearAcceleration"},
|
||||
},
|
||||
"Mass": {
|
||||
"base_unit": "Kilograms",
|
||||
"multiply": {"LinearAcceleration": "Force"},
|
||||
"divide": {},
|
||||
},
|
||||
"MomentOfInertia": {
|
||||
"base_unit": "KilogramSquareMeters",
|
||||
"multiply": {"AngularVelocity": "AngularMomentum"},
|
||||
"divide": {},
|
||||
},
|
||||
"Mult": {
|
||||
"base_unit": "unit()",
|
||||
"generics": {"A": {"extends": "Unit"}, "B": {"extends": "Unit"}},
|
||||
"multiply": {},
|
||||
"divide": {},
|
||||
},
|
||||
"Per": {
|
||||
"base_unit": "unit()",
|
||||
"generics": {"Dividend": {"extends": "Unit"}, "Divisor": {"extends": "Unit"}},
|
||||
"multiply": {},
|
||||
"divide": {},
|
||||
"extra": inspect.cleandoc(
|
||||
"""
|
||||
default Measure<Dividend> timesDivisor(Measure<? extends Divisor> multiplier) {
|
||||
return (Measure<Dividend>) baseUnit().numerator().ofBaseUnits(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
default Measure<? extends PerUnit<Divisor, Dividend>> reciprocal() {
|
||||
// May return a velocity if Divisor == TimeUnit, so we can't guarantee a "Per" instance
|
||||
return baseUnit().reciprocal().ofBaseUnits(1 / baseUnitMagnitude());
|
||||
}
|
||||
"""
|
||||
),
|
||||
},
|
||||
"Power": {
|
||||
"base_unit": "Watts",
|
||||
"multiply": {
|
||||
"Time": "Energy",
|
||||
},
|
||||
"divide": {"Voltage": "Current", "Current": "Voltage", "Energy": "Frequency"},
|
||||
},
|
||||
"Temperature": {"base_unit": "Kelvin", "multiply": {}, "divide": {}},
|
||||
"Time": {
|
||||
"base_unit": "Seconds",
|
||||
"multiply": {
|
||||
"Frequency": "Dimensionless",
|
||||
"AngularVelocity": "Angle",
|
||||
"AngularAcceleration": "AngularVelocity",
|
||||
"LinearVelocity": "Distance",
|
||||
"LinearAcceleration": "LinearVelocity",
|
||||
# TODO:
|
||||
# "Acceleration<D>": "Velocity<D>"
|
||||
# "Velocity<D>": "Measure<D>"
|
||||
},
|
||||
"divide": {
|
||||
# Time specifically needs this to be called out so generated methods like
|
||||
# `per(TimeUnit)` or `divide(Time)` will return dimensionless values instead of
|
||||
# `Velocity<TimeUnit>` (i.e. a time per unit time ratio)
|
||||
"Time": "Dimensionless"
|
||||
},
|
||||
"extra": inspect.cleandoc(
|
||||
"""
|
||||
default Frequency asFrequency() { return Hertz.of(1 / baseUnitMagnitude()); }
|
||||
"""
|
||||
),
|
||||
},
|
||||
"Torque": {
|
||||
"base_unit": "NewtonMeters",
|
||||
"multiply": {},
|
||||
"divide": {"Distance": "Force", "Force": "Distance"},
|
||||
},
|
||||
"Velocity": {
|
||||
"base_unit": "unit()",
|
||||
"generics": {"D": {"extends": "Unit"}},
|
||||
"multiply": {},
|
||||
"divide": {},
|
||||
},
|
||||
"Voltage": {"base_unit": "Volts", "multiply": {"Current": "Power"}, "divide": {}},
|
||||
}
|
||||
|
||||
|
||||
def generics_list(measure_name):
|
||||
if "generics" in UNIT_CONFIGURATIONS[measure_name]:
|
||||
args = []
|
||||
for name, config in UNIT_CONFIGURATIONS[measure_name]["generics"].items():
|
||||
if "extends" in config:
|
||||
args.append("{} extends {}".format(name, config["extends"]))
|
||||
elif "super" in config:
|
||||
args.append("{} super {}".format(name, config["super"]))
|
||||
else:
|
||||
args.append(name)
|
||||
|
||||
return "<{}>".format(", ".join(args))
|
||||
else:
|
||||
return ""
|
||||
|
||||
|
||||
def generics_usage(measure_name):
|
||||
if "generics" in UNIT_CONFIGURATIONS[measure_name]:
|
||||
args = UNIT_CONFIGURATIONS[measure_name]["generics"].keys()
|
||||
|
||||
return "<{}>".format(", ".join(args))
|
||||
else:
|
||||
return ""
|
||||
|
||||
|
||||
def type_decl(measure_name):
|
||||
return measure_name + generics_list(measure_name)
|
||||
|
||||
|
||||
def type_usage(measure_name):
|
||||
return measure_name + generics_usage(measure_name)
|
||||
|
||||
|
||||
# measure-to-unit
|
||||
def mtou(measure_name):
|
||||
if (
|
||||
measure_name in UNIT_CONFIGURATIONS
|
||||
and "generics" in UNIT_CONFIGURATIONS[measure_name]
|
||||
):
|
||||
return "{}Unit{}".format(measure_name, generics_usage(measure_name))
|
||||
else:
|
||||
regex = re.compile(r"^(.*?)(<.*>)?$")
|
||||
return re.sub(regex, "\\1Unit\\2", measure_name)
|
||||
|
||||
|
||||
def main():
|
||||
|
||||
dirname, _ = os.path.split(os.path.abspath(__file__))
|
||||
|
||||
env = Environment(
|
||||
loader=FileSystemLoader(f"{dirname}/src/generate/main/java"),
|
||||
autoescape=False,
|
||||
keep_trailing_newline=True,
|
||||
)
|
||||
|
||||
interfaceTemplate = env.get_template("Measure-interface.java.jinja")
|
||||
immutableTemplate = env.get_template("Measure-immutable.java.jinja")
|
||||
mutableTemplate = env.get_template("Measure-mutable.java.jinja")
|
||||
rootPath = f"{dirname}/src/generated/main/java/edu/wpi/first/units"
|
||||
|
||||
helpers = {
|
||||
"type_decl": type_decl,
|
||||
"type_usage": type_usage,
|
||||
"generics_list": generics_list,
|
||||
"generics_usage": generics_usage,
|
||||
"mtou": mtou,
|
||||
}
|
||||
|
||||
for unit_name in UNIT_CONFIGURATIONS:
|
||||
interfaceContents = interfaceTemplate.render(
|
||||
name=unit_name,
|
||||
math_units=MATH_OPERATION_UNITS,
|
||||
config=UNIT_CONFIGURATIONS,
|
||||
helpers=helpers,
|
||||
)
|
||||
immutableContents = immutableTemplate.render(
|
||||
name=unit_name,
|
||||
units=MATH_OPERATION_UNITS,
|
||||
config=UNIT_CONFIGURATIONS,
|
||||
helpers=helpers,
|
||||
)
|
||||
mutableContents = mutableTemplate.render(
|
||||
name=unit_name,
|
||||
units=MATH_OPERATION_UNITS,
|
||||
config=UNIT_CONFIGURATIONS,
|
||||
helpers=helpers,
|
||||
)
|
||||
|
||||
output(f"{rootPath}/measure", f"{unit_name}.java", interfaceContents)
|
||||
output(f"{rootPath}/measure", f"Immutable{unit_name}.java", immutableContents)
|
||||
output(f"{rootPath}/measure", f"Mut{unit_name}.java", mutableContents)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
28
wpiunits/src/generate/main/java/Measure-immutable.java.jinja
Normal file
28
wpiunits/src/generate/main/java/Measure-immutable.java.jinja
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record Immutable{{ helpers['type_decl'](name) }}(double magnitude, double baseUnitMagnitude, {{ helpers['mtou'](name) }} unit) implements {{ helpers['type_usage'](name) }} {
|
||||
@Override
|
||||
public {{ helpers['type_usage'](name) }} copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
117
wpiunits/src/generate/main/java/Measure-interface.java.jinja
Normal file
117
wpiunits/src/generate/main/java/Measure-interface.java.jinja
Normal file
@@ -0,0 +1,117 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface {{ helpers['type_decl'](name) }} extends Measure<{{ helpers['mtou'](name) }}> {
|
||||
static {{ helpers['generics_list'](name) }} {{ helpers['type_usage'](name) }} ofRelativeUnits(double magnitude, {{ helpers['mtou'](name) }} unit) {
|
||||
return new Immutable{{ helpers['type_usage'](name) }}(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static {{ helpers['generics_list'](name) }} {{ helpers['type_usage'](name) }} ofBaseUnits(double baseUnitMagnitude, {{ helpers['mtou'](name) }} unit) {
|
||||
return new Immutable{{ helpers['type_usage'](name) }}(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
{{ helpers['type_usage'](name) }} copy();
|
||||
|
||||
@Override
|
||||
default Mut{{ helpers['type_usage'](name) }} mutableCopy() {
|
||||
return new Mut{{ helpers['type_usage'](name) }}(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
{{ helpers['mtou'](name) }} unit();
|
||||
|
||||
@Override
|
||||
default {{ helpers['mtou'](name) }} baseUnit() { return ({{ helpers['mtou'](name) }}) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in({{ helpers['mtou'](name) }} unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} unaryMinus() {
|
||||
return ({{ helpers['type_usage'](name) }}) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} plus(Measure<? extends {{ helpers['mtou'](name) }}> other) {
|
||||
return ({{ helpers['type_usage'](name) }}) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} minus(Measure<? extends {{ helpers['mtou'](name) }}> other) {
|
||||
return ({{ helpers['type_usage'](name) }}) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} times(double multiplier) {
|
||||
return ({{ helpers['type_usage'](name) }}) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} divide(double divisor) {
|
||||
return ({{ helpers['type_usage'](name) }}) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ config[name]['divide']['Time'] or "Velocity<{}>".format(helpers['mtou'](name)) }} per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
{% for unit in math_units -%}
|
||||
{% if unit == "Dimensionless" %}
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} divide({{ unit }} divisor) {
|
||||
return ({{ helpers['type_usage'](name) }}) {{ config[name]['base_unit'] }}.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default {{ helpers['type_usage'](name) }} times({{ unit }} multiplier) {
|
||||
return ({{ helpers['type_usage'](name) }}) {{ config[name]['base_unit'] }}.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
{% else %}
|
||||
{% if unit in config[name]['multiply'] %}
|
||||
@Override
|
||||
default {{ config[name]['multiply'][unit] }} times({{ unit }} multiplier) {
|
||||
return {{ config[config[name]['multiply'][unit]]['base_unit'] }}.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
{% else %}
|
||||
@Override
|
||||
default Mult<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}> times({{ unit }} multiplier) {
|
||||
return (Mult<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}>) Measure.super.times(multiplier);
|
||||
}
|
||||
{% endif -%}
|
||||
{% if unit in config[name]['divide'] %}
|
||||
@Override
|
||||
default {{ config[name]['divide'][unit] }} divide({{ unit }} divisor) {
|
||||
return {{ config[config[name]['divide'][unit]]['base_unit'] }}.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
{% elif unit == "Time" %}
|
||||
@Override
|
||||
default Velocity<{{ helpers['mtou'](name) }}> divide({{ unit }} divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
{% elif unit == name %}
|
||||
@Override
|
||||
default Dimensionless divide({{ unit }} divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
{% else %}
|
||||
@Override
|
||||
default Per<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}> divide({{ unit }} divisor) {
|
||||
return (Per<{{ helpers['mtou'](name) }}, {{ helpers['mtou'](unit) }}>) Measure.super.divide(divisor);
|
||||
}
|
||||
{% endif -%}
|
||||
{% endif -%}
|
||||
{% endfor -%}
|
||||
{{ config[name]['extra'] }}
|
||||
}
|
||||
25
wpiunits/src/generate/main/java/Measure-mutable.java.jinja
Normal file
25
wpiunits/src/generate/main/java/Measure-mutable.java.jinja
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class Mut{{ helpers['type_decl'](name) }}
|
||||
extends MutableMeasureBase<{{ helpers['mtou'](name) }}, {{ helpers['type_usage'](name) }}, Mut{{ helpers['type_usage'](name) }}>
|
||||
implements {{ helpers['type_usage'](name) }} {
|
||||
public Mut{{ name }}(double magnitude, double baseUnitMagnitude, {{ helpers['mtou'](name) }} unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public {{ helpers['type_usage'](name) }} copy() {
|
||||
return new Immutable{{ helpers['type_usage'](name) }}(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Acceleration<D extends Unit> extends Measure<AccelerationUnit<D>> {
|
||||
static <D extends Unit> Acceleration<D> ofRelativeUnits(double magnitude, AccelerationUnit<D> unit) {
|
||||
return new ImmutableAcceleration<D>(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static <D extends Unit> Acceleration<D> ofBaseUnits(double baseUnitMagnitude, AccelerationUnit<D> unit) {
|
||||
return new ImmutableAcceleration<D>(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Acceleration<D> copy();
|
||||
|
||||
@Override
|
||||
default MutAcceleration<D> mutableCopy() {
|
||||
return new MutAcceleration<D>(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
AccelerationUnit<D> unit();
|
||||
|
||||
@Override
|
||||
default AccelerationUnit<D> baseUnit() { return (AccelerationUnit<D>) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(AccelerationUnit<D> unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> unaryMinus() {
|
||||
return (Acceleration<D>) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> plus(Measure<? extends AccelerationUnit<D>> other) {
|
||||
return (Acceleration<D>) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> minus(Measure<? extends AccelerationUnit<D>> other) {
|
||||
return (Acceleration<D>) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> times(double multiplier) {
|
||||
return (Acceleration<D>) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> divide(double divisor) {
|
||||
return (Acceleration<D>) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AccelerationUnit<D>> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<AccelerationUnit<D>, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<AccelerationUnit<D>, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<AccelerationUnit<D>, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<AccelerationUnit<D>, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<AccelerationUnit<D>, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<AccelerationUnit<D>, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> divide(Dimensionless divisor) {
|
||||
return (Acceleration<D>) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Acceleration<D> times(Dimensionless multiplier) {
|
||||
return (Acceleration<D>) unit().of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<AccelerationUnit<D>, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<AccelerationUnit<D>, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, ForceUnit> divide(Force divisor) {
|
||||
return (Per<AccelerationUnit<D>, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<AccelerationUnit<D>, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<AccelerationUnit<D>, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<AccelerationUnit<D>, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<AccelerationUnit<D>, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, MassUnit> divide(Mass divisor) {
|
||||
return (Per<AccelerationUnit<D>, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<AccelerationUnit<D>, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<AccelerationUnit<D>, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<AccelerationUnit<D>, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, PowerUnit> divide(Power divisor) {
|
||||
return (Per<AccelerationUnit<D>, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<AccelerationUnit<D>, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AccelerationUnit<D>> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<AccelerationUnit<D>, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<AccelerationUnit<D>, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AccelerationUnit<D>, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<AccelerationUnit<D>, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AccelerationUnit<D>, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<AccelerationUnit<D>, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Angle extends Measure<AngleUnit> {
|
||||
static Angle ofRelativeUnits(double magnitude, AngleUnit unit) {
|
||||
return new ImmutableAngle(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Angle ofBaseUnits(double baseUnitMagnitude, AngleUnit unit) {
|
||||
return new ImmutableAngle(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Angle copy();
|
||||
|
||||
@Override
|
||||
default MutAngle mutableCopy() {
|
||||
return new MutAngle(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
AngleUnit unit();
|
||||
|
||||
@Override
|
||||
default AngleUnit baseUnit() { return (AngleUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(AngleUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle unaryMinus() {
|
||||
return (Angle) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle plus(Measure<? extends AngleUnit> other) {
|
||||
return (Angle) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle minus(Measure<? extends AngleUnit> other) {
|
||||
return (Angle) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle times(double multiplier) {
|
||||
return (Angle) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle divide(double divisor) {
|
||||
return (Angle) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<AngleUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<AngleUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<AngleUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Angle divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<AngleUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<AngleUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<AngleUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<AngleUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<AngleUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<AngleUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<AngleUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<AngleUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle divide(Dimensionless divisor) {
|
||||
return (Angle) Radians.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Angle times(Dimensionless multiplier) {
|
||||
return (Angle) Radians.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<AngleUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<AngleUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<AngleUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<AngleUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<AngleUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<AngleUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(Frequency multiplier) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<AngleUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<AngleUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<AngleUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<AngleUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<AngleUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<AngleUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<AngleUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<AngleUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<AngleUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<AngleUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<AngleUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<AngleUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<AngleUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<AngleUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<AngleUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<AngleUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<AngleUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<AngleUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<AngleUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<AngleUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity divide(Time divisor) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<AngleUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<AngleUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<AngleUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<AngleUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngleUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<AngleUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngleUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<AngleUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface AngularAcceleration extends Measure<AngularAccelerationUnit> {
|
||||
static AngularAcceleration ofRelativeUnits(double magnitude, AngularAccelerationUnit unit) {
|
||||
return new ImmutableAngularAcceleration(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static AngularAcceleration ofBaseUnits(double baseUnitMagnitude, AngularAccelerationUnit unit) {
|
||||
return new ImmutableAngularAcceleration(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularAcceleration copy();
|
||||
|
||||
@Override
|
||||
default MutAngularAcceleration mutableCopy() {
|
||||
return new MutAngularAcceleration(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularAccelerationUnit unit();
|
||||
|
||||
@Override
|
||||
default AngularAccelerationUnit baseUnit() { return (AngularAccelerationUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(AngularAccelerationUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration unaryMinus() {
|
||||
return (AngularAcceleration) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration plus(Measure<? extends AngularAccelerationUnit> other) {
|
||||
return (AngularAcceleration) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration minus(Measure<? extends AngularAccelerationUnit> other) {
|
||||
return (AngularAcceleration) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration times(double multiplier) {
|
||||
return (AngularAcceleration) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration divide(double divisor) {
|
||||
return (AngularAcceleration) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AngularAccelerationUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<AngularAccelerationUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<AngularAccelerationUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(AngularAcceleration divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<AngularAccelerationUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<AngularAccelerationUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<AngularAccelerationUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration divide(Dimensionless divisor) {
|
||||
return (AngularAcceleration) RadiansPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration times(Dimensionless multiplier) {
|
||||
return (AngularAcceleration) RadiansPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<AngularAccelerationUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<AngularAccelerationUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<AngularAccelerationUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity divide(Frequency divisor) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<AngularAccelerationUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<AngularAccelerationUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<AngularAccelerationUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<AngularAccelerationUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<AngularAccelerationUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<AngularAccelerationUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<AngularAccelerationUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<AngularAccelerationUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<AngularAccelerationUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(Time multiplier) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AngularAccelerationUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<AngularAccelerationUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<AngularAccelerationUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularAccelerationUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<AngularAccelerationUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularAccelerationUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<AngularAccelerationUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface AngularMomentum extends Measure<AngularMomentumUnit> {
|
||||
static AngularMomentum ofRelativeUnits(double magnitude, AngularMomentumUnit unit) {
|
||||
return new ImmutableAngularMomentum(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static AngularMomentum ofBaseUnits(double baseUnitMagnitude, AngularMomentumUnit unit) {
|
||||
return new ImmutableAngularMomentum(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularMomentum copy();
|
||||
|
||||
@Override
|
||||
default MutAngularMomentum mutableCopy() {
|
||||
return new MutAngularMomentum(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularMomentumUnit unit();
|
||||
|
||||
@Override
|
||||
default AngularMomentumUnit baseUnit() { return (AngularMomentumUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(AngularMomentumUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum unaryMinus() {
|
||||
return (AngularMomentum) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum plus(Measure<? extends AngularMomentumUnit> other) {
|
||||
return (AngularMomentum) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum minus(Measure<? extends AngularMomentumUnit> other) {
|
||||
return (AngularMomentum) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum times(double multiplier) {
|
||||
return (AngularMomentum) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum divide(double divisor) {
|
||||
return (AngularMomentum) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AngularMomentumUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<AngularMomentumUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<AngularMomentumUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<AngularMomentumUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<AngularMomentumUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<AngularMomentumUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<AngularMomentumUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<AngularMomentumUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(AngularMomentum divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<AngularMomentumUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia divide(AngularVelocity divisor) {
|
||||
return KilogramSquareMeters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<AngularMomentumUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<AngularMomentumUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum divide(Dimensionless divisor) {
|
||||
return (AngularMomentum) KilogramMetersSquaredPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularMomentum times(Dimensionless multiplier) {
|
||||
return (AngularMomentum) KilogramMetersSquaredPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<AngularMomentumUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<AngularMomentumUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<AngularMomentumUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<AngularMomentumUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<AngularMomentumUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<AngularMomentumUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<AngularMomentumUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<AngularMomentumUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<AngularMomentumUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<AngularMomentumUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<AngularMomentumUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<AngularMomentumUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<AngularMomentumUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<AngularMomentumUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<AngularMomentumUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<AngularMomentumUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<AngularMomentumUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<AngularMomentumUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<AngularMomentumUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<AngularMomentumUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<AngularMomentumUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<AngularMomentumUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<AngularMomentumUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<AngularMomentumUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<AngularMomentumUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<AngularMomentumUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<AngularMomentumUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<AngularMomentumUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<AngularMomentumUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<AngularMomentumUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<AngularMomentumUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<AngularMomentumUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularMomentumUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<AngularMomentumUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularMomentumUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<AngularMomentumUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface AngularVelocity extends Measure<AngularVelocityUnit> {
|
||||
static AngularVelocity ofRelativeUnits(double magnitude, AngularVelocityUnit unit) {
|
||||
return new ImmutableAngularVelocity(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static AngularVelocity ofBaseUnits(double baseUnitMagnitude, AngularVelocityUnit unit) {
|
||||
return new ImmutableAngularVelocity(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularVelocity copy();
|
||||
|
||||
@Override
|
||||
default MutAngularVelocity mutableCopy() {
|
||||
return new MutAngularVelocity(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
AngularVelocityUnit unit();
|
||||
|
||||
@Override
|
||||
default AngularVelocityUnit baseUnit() { return (AngularVelocityUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(AngularVelocityUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity unaryMinus() {
|
||||
return (AngularVelocity) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity plus(Measure<? extends AngularVelocityUnit> other) {
|
||||
return (AngularVelocity) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity minus(Measure<? extends AngularVelocityUnit> other) {
|
||||
return (AngularVelocity) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(double multiplier) {
|
||||
return (AngularVelocity) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity divide(double divisor) {
|
||||
return (AngularVelocity) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<AngularVelocityUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<AngularVelocityUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<AngularVelocityUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<AngularVelocityUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<AngularVelocityUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<AngularVelocityUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<AngularVelocityUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<AngularVelocityUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<AngularVelocityUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(AngularVelocity divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<AngularVelocityUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<AngularVelocityUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity divide(Dimensionless divisor) {
|
||||
return (AngularVelocity) RadiansPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(Dimensionless multiplier) {
|
||||
return (AngularVelocity) RadiansPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<AngularVelocityUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<AngularVelocityUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<AngularVelocityUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<AngularVelocityUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<AngularVelocityUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<AngularVelocityUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularAcceleration times(Frequency multiplier) {
|
||||
return RadiansPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<AngularVelocityUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<AngularVelocityUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<AngularVelocityUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<AngularVelocityUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<AngularVelocityUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<AngularVelocityUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<AngularVelocityUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<AngularVelocityUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<AngularVelocityUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<AngularVelocityUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<AngularVelocityUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<AngularVelocityUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<AngularVelocityUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<AngularVelocityUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<AngularVelocityUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<AngularVelocityUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<AngularVelocityUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<AngularVelocityUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<AngularVelocityUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Angle times(Time multiplier) {
|
||||
return Radians.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default AngularAcceleration divide(Time divisor) {
|
||||
return RadiansPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<AngularVelocityUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<AngularVelocityUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<AngularVelocityUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<AngularVelocityUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<AngularVelocityUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<AngularVelocityUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<AngularVelocityUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<AngularVelocityUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
default Frequency asFrequency() { return Hertz.of(baseUnitMagnitude()); }
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Current extends Measure<CurrentUnit> {
|
||||
static Current ofRelativeUnits(double magnitude, CurrentUnit unit) {
|
||||
return new ImmutableCurrent(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Current ofBaseUnits(double baseUnitMagnitude, CurrentUnit unit) {
|
||||
return new ImmutableCurrent(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Current copy();
|
||||
|
||||
@Override
|
||||
default MutCurrent mutableCopy() {
|
||||
return new MutCurrent(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
CurrentUnit unit();
|
||||
|
||||
@Override
|
||||
default CurrentUnit baseUnit() { return (CurrentUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(CurrentUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current unaryMinus() {
|
||||
return (Current) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current plus(Measure<? extends CurrentUnit> other) {
|
||||
return (Current) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current minus(Measure<? extends CurrentUnit> other) {
|
||||
return (Current) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current times(double multiplier) {
|
||||
return (Current) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current divide(double divisor) {
|
||||
return (Current) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<CurrentUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<CurrentUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<CurrentUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<CurrentUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<CurrentUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<CurrentUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<CurrentUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<CurrentUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<CurrentUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<CurrentUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<CurrentUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<CurrentUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Current divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current divide(Dimensionless divisor) {
|
||||
return (Current) Amps.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Current times(Dimensionless multiplier) {
|
||||
return (Current) Amps.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<CurrentUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<CurrentUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<CurrentUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<CurrentUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<CurrentUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<CurrentUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<CurrentUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<CurrentUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<CurrentUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<CurrentUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<CurrentUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<CurrentUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<CurrentUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<CurrentUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<CurrentUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<CurrentUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<CurrentUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<CurrentUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<CurrentUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<CurrentUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<CurrentUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<CurrentUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<CurrentUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<CurrentUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<CurrentUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<CurrentUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<CurrentUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<CurrentUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<CurrentUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<CurrentUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<CurrentUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<CurrentUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<CurrentUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Power times(Voltage multiplier) {
|
||||
return Watts.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<CurrentUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<CurrentUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Dimensionless extends Measure<DimensionlessUnit> {
|
||||
static Dimensionless ofRelativeUnits(double magnitude, DimensionlessUnit unit) {
|
||||
return new ImmutableDimensionless(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Dimensionless ofBaseUnits(double baseUnitMagnitude, DimensionlessUnit unit) {
|
||||
return new ImmutableDimensionless(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Dimensionless copy();
|
||||
|
||||
@Override
|
||||
default MutDimensionless mutableCopy() {
|
||||
return new MutDimensionless(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
DimensionlessUnit unit();
|
||||
|
||||
@Override
|
||||
default DimensionlessUnit baseUnit() { return (DimensionlessUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(DimensionlessUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless unaryMinus() {
|
||||
return (Dimensionless) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless plus(Measure<? extends DimensionlessUnit> other) {
|
||||
return (Dimensionless) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless minus(Measure<? extends DimensionlessUnit> other) {
|
||||
return (Dimensionless) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless times(double multiplier) {
|
||||
return (Dimensionless) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(double divisor) {
|
||||
return (Dimensionless) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DimensionlessUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<DimensionlessUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<DimensionlessUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Angle times(Angle multiplier) {
|
||||
return Radians.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<DimensionlessUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularAcceleration times(AngularAcceleration multiplier) {
|
||||
return RadiansPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<DimensionlessUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularMomentum times(AngularMomentum multiplier) {
|
||||
return KilogramMetersSquaredPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<DimensionlessUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(AngularVelocity multiplier) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<DimensionlessUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Current times(Current multiplier) {
|
||||
return Amps.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<DimensionlessUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Dimensionless divisor) {
|
||||
return (Dimensionless) Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless times(Dimensionless multiplier) {
|
||||
return (Dimensionless) Value.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Distance times(Distance multiplier) {
|
||||
return Meters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<DimensionlessUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Energy times(Energy multiplier) {
|
||||
return Joules.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<DimensionlessUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Force times(Force multiplier) {
|
||||
return Newtons.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<DimensionlessUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Frequency times(Frequency multiplier) {
|
||||
return Hertz.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<DimensionlessUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearAcceleration times(LinearAcceleration multiplier) {
|
||||
return MetersPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<DimensionlessUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearMomentum times(LinearMomentum multiplier) {
|
||||
return KilogramMetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<DimensionlessUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(LinearVelocity multiplier) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<DimensionlessUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mass times(Mass multiplier) {
|
||||
return Kilograms.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<DimensionlessUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default MomentOfInertia times(MomentOfInertia multiplier) {
|
||||
return KilogramSquareMeters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<DimensionlessUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DimensionlessUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<DimensionlessUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<DimensionlessUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DimensionlessUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<DimensionlessUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<DimensionlessUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Power times(Power multiplier) {
|
||||
return Watts.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<DimensionlessUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Temperature times(Temperature multiplier) {
|
||||
return Kelvin.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<DimensionlessUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Time times(Time multiplier) {
|
||||
return Seconds.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency divide(Time divisor) {
|
||||
return Hertz.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Torque times(Torque multiplier) {
|
||||
return NewtonMeters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<DimensionlessUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DimensionlessUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<DimensionlessUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<DimensionlessUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Voltage times(Voltage multiplier) {
|
||||
return Volts.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DimensionlessUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<DimensionlessUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Distance extends Measure<DistanceUnit> {
|
||||
static Distance ofRelativeUnits(double magnitude, DistanceUnit unit) {
|
||||
return new ImmutableDistance(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Distance ofBaseUnits(double baseUnitMagnitude, DistanceUnit unit) {
|
||||
return new ImmutableDistance(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Distance copy();
|
||||
|
||||
@Override
|
||||
default MutDistance mutableCopy() {
|
||||
return new MutDistance(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
DistanceUnit unit();
|
||||
|
||||
@Override
|
||||
default DistanceUnit baseUnit() { return (DistanceUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(DistanceUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance unaryMinus() {
|
||||
return (Distance) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance plus(Measure<? extends DistanceUnit> other) {
|
||||
return (Distance) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance minus(Measure<? extends DistanceUnit> other) {
|
||||
return (Distance) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance times(double multiplier) {
|
||||
return (Distance) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance divide(double divisor) {
|
||||
return (Distance) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<DistanceUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<DistanceUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<DistanceUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<DistanceUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<DistanceUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<DistanceUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<DistanceUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<DistanceUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<DistanceUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<DistanceUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<DistanceUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<DistanceUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance divide(Dimensionless divisor) {
|
||||
return (Distance) Meters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Distance times(Dimensionless multiplier) {
|
||||
return (Distance) Meters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<DistanceUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Distance divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<DistanceUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<DistanceUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Torque times(Force multiplier) {
|
||||
return NewtonMeters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<DistanceUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(Frequency multiplier) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<DistanceUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<DistanceUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<DistanceUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<DistanceUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<DistanceUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<DistanceUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Time divide(LinearVelocity divisor) {
|
||||
return Seconds.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<DistanceUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<DistanceUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<DistanceUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<DistanceUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<DistanceUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<DistanceUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<DistanceUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<DistanceUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<DistanceUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<DistanceUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<DistanceUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<DistanceUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<DistanceUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity divide(Time divisor) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<DistanceUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<DistanceUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<DistanceUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<DistanceUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<DistanceUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<DistanceUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<DistanceUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<DistanceUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Energy extends Measure<EnergyUnit> {
|
||||
static Energy ofRelativeUnits(double magnitude, EnergyUnit unit) {
|
||||
return new ImmutableEnergy(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Energy ofBaseUnits(double baseUnitMagnitude, EnergyUnit unit) {
|
||||
return new ImmutableEnergy(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Energy copy();
|
||||
|
||||
@Override
|
||||
default MutEnergy mutableCopy() {
|
||||
return new MutEnergy(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
EnergyUnit unit();
|
||||
|
||||
@Override
|
||||
default EnergyUnit baseUnit() { return (EnergyUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(EnergyUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy unaryMinus() {
|
||||
return (Energy) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy plus(Measure<? extends EnergyUnit> other) {
|
||||
return (Energy) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy minus(Measure<? extends EnergyUnit> other) {
|
||||
return (Energy) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy times(double multiplier) {
|
||||
return (Energy) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy divide(double divisor) {
|
||||
return (Energy) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Power per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<EnergyUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<EnergyUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<EnergyUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<EnergyUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<EnergyUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<EnergyUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<EnergyUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<EnergyUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<EnergyUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<EnergyUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<EnergyUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<EnergyUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy divide(Dimensionless divisor) {
|
||||
return (Energy) Joules.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Energy times(Dimensionless multiplier) {
|
||||
return (Energy) Joules.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<EnergyUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<EnergyUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<EnergyUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Energy divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<EnergyUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<EnergyUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Power times(Frequency multiplier) {
|
||||
return Watts.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<EnergyUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<EnergyUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<EnergyUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<EnergyUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<EnergyUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<EnergyUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<EnergyUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<EnergyUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<EnergyUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<EnergyUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<EnergyUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<EnergyUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<EnergyUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<EnergyUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<EnergyUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<EnergyUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<EnergyUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<EnergyUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<EnergyUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<EnergyUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Power divide(Time divisor) {
|
||||
return Watts.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<EnergyUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<EnergyUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<EnergyUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<EnergyUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<EnergyUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<EnergyUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<EnergyUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<EnergyUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Force extends Measure<ForceUnit> {
|
||||
static Force ofRelativeUnits(double magnitude, ForceUnit unit) {
|
||||
return new ImmutableForce(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Force ofBaseUnits(double baseUnitMagnitude, ForceUnit unit) {
|
||||
return new ImmutableForce(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Force copy();
|
||||
|
||||
@Override
|
||||
default MutForce mutableCopy() {
|
||||
return new MutForce(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
ForceUnit unit();
|
||||
|
||||
@Override
|
||||
default ForceUnit baseUnit() { return (ForceUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(ForceUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force unaryMinus() {
|
||||
return (Force) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force plus(Measure<? extends ForceUnit> other) {
|
||||
return (Force) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force minus(Measure<? extends ForceUnit> other) {
|
||||
return (Force) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force times(double multiplier) {
|
||||
return (Force) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force divide(double divisor) {
|
||||
return (Force) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<ForceUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<ForceUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<ForceUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<ForceUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<ForceUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<ForceUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<ForceUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<ForceUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<ForceUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<ForceUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<ForceUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<ForceUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<ForceUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force divide(Dimensionless divisor) {
|
||||
return (Force) Newtons.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force times(Dimensionless multiplier) {
|
||||
return (Force) Newtons.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Energy times(Distance multiplier) {
|
||||
return Joules.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<ForceUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<ForceUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<ForceUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<ForceUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Force divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<ForceUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<ForceUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<ForceUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass divide(LinearAcceleration divisor) {
|
||||
return Kilograms.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<ForceUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<ForceUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<ForceUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<ForceUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<ForceUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration divide(Mass divisor) {
|
||||
return MetersPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<ForceUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<ForceUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<ForceUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<ForceUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<ForceUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<ForceUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<ForceUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<ForceUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<ForceUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<ForceUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<ForceUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<ForceUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<ForceUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<ForceUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<ForceUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<ForceUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<ForceUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<ForceUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<ForceUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<ForceUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
335
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java
generated
Normal file
335
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java
generated
Normal file
@@ -0,0 +1,335 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Frequency extends Measure<FrequencyUnit> {
|
||||
static Frequency ofRelativeUnits(double magnitude, FrequencyUnit unit) {
|
||||
return new ImmutableFrequency(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Frequency ofBaseUnits(double baseUnitMagnitude, FrequencyUnit unit) {
|
||||
return new ImmutableFrequency(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Frequency copy();
|
||||
|
||||
@Override
|
||||
default MutFrequency mutableCopy() {
|
||||
return new MutFrequency(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
FrequencyUnit unit();
|
||||
|
||||
@Override
|
||||
default FrequencyUnit baseUnit() { return (FrequencyUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(FrequencyUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency unaryMinus() {
|
||||
return (Frequency) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency plus(Measure<? extends FrequencyUnit> other) {
|
||||
return (Frequency) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency minus(Measure<? extends FrequencyUnit> other) {
|
||||
return (Frequency) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency times(double multiplier) {
|
||||
return (Frequency) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency divide(double divisor) {
|
||||
return (Frequency) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<FrequencyUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<FrequencyUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<FrequencyUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularVelocity times(Angle multiplier) {
|
||||
return RadiansPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<FrequencyUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<FrequencyUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<FrequencyUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<FrequencyUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<FrequencyUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularAcceleration times(AngularVelocity multiplier) {
|
||||
return RadiansPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<FrequencyUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<FrequencyUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<FrequencyUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency divide(Dimensionless divisor) {
|
||||
return (Frequency) Hertz.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Frequency times(Dimensionless multiplier) {
|
||||
return (Frequency) Hertz.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(Distance multiplier) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<FrequencyUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<FrequencyUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<FrequencyUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<FrequencyUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<FrequencyUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<FrequencyUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Frequency divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<FrequencyUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<FrequencyUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<FrequencyUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<FrequencyUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearAcceleration times(LinearVelocity multiplier) {
|
||||
return MetersPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<FrequencyUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<FrequencyUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<FrequencyUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<FrequencyUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<FrequencyUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<FrequencyUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<FrequencyUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<FrequencyUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<FrequencyUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<FrequencyUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<FrequencyUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<FrequencyUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<FrequencyUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Dimensionless times(Time multiplier) {
|
||||
return Value.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<FrequencyUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<FrequencyUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<FrequencyUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<FrequencyUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<FrequencyUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<FrequencyUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<FrequencyUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<FrequencyUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<FrequencyUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
/** Converts this frequency to the time period between cycles. */
|
||||
default Time asPeriod() { return Seconds.of(1 / baseUnitMagnitude()); }
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAcceleration.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAcceleration.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableAcceleration<D extends Unit>(double magnitude, double baseUnitMagnitude, AccelerationUnit<D> unit) implements Acceleration<D> {
|
||||
@Override
|
||||
public Acceleration<D> copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngle.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngle.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableAngle(double magnitude, double baseUnitMagnitude, AngleUnit unit) implements Angle {
|
||||
@Override
|
||||
public Angle copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularAcceleration.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularAcceleration.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableAngularAcceleration(double magnitude, double baseUnitMagnitude, AngularAccelerationUnit unit) implements AngularAcceleration {
|
||||
@Override
|
||||
public AngularAcceleration copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularMomentum.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularMomentum.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableAngularMomentum(double magnitude, double baseUnitMagnitude, AngularMomentumUnit unit) implements AngularMomentum {
|
||||
@Override
|
||||
public AngularMomentum copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularVelocity.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularVelocity.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableAngularVelocity(double magnitude, double baseUnitMagnitude, AngularVelocityUnit unit) implements AngularVelocity {
|
||||
@Override
|
||||
public AngularVelocity copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableCurrent.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableCurrent.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableCurrent(double magnitude, double baseUnitMagnitude, CurrentUnit unit) implements Current {
|
||||
@Override
|
||||
public Current copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDimensionless.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDimensionless.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableDimensionless(double magnitude, double baseUnitMagnitude, DimensionlessUnit unit) implements Dimensionless {
|
||||
@Override
|
||||
public Dimensionless copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDistance.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDistance.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableDistance(double magnitude, double baseUnitMagnitude, DistanceUnit unit) implements Distance {
|
||||
@Override
|
||||
public Distance copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableEnergy.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableEnergy.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableEnergy(double magnitude, double baseUnitMagnitude, EnergyUnit unit) implements Energy {
|
||||
@Override
|
||||
public Energy copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableForce.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableForce.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableForce(double magnitude, double baseUnitMagnitude, ForceUnit unit) implements Force {
|
||||
@Override
|
||||
public Force copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableFrequency.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableFrequency.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableFrequency(double magnitude, double baseUnitMagnitude, FrequencyUnit unit) implements Frequency {
|
||||
@Override
|
||||
public Frequency copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearAcceleration.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearAcceleration.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableLinearAcceleration(double magnitude, double baseUnitMagnitude, LinearAccelerationUnit unit) implements LinearAcceleration {
|
||||
@Override
|
||||
public LinearAcceleration copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearMomentum.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearMomentum.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableLinearMomentum(double magnitude, double baseUnitMagnitude, LinearMomentumUnit unit) implements LinearMomentum {
|
||||
@Override
|
||||
public LinearMomentum copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearVelocity.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearVelocity.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableLinearVelocity(double magnitude, double baseUnitMagnitude, LinearVelocityUnit unit) implements LinearVelocity {
|
||||
@Override
|
||||
public LinearVelocity copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMass.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMass.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableMass(double magnitude, double baseUnitMagnitude, MassUnit unit) implements Mass {
|
||||
@Override
|
||||
public Mass copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMomentOfInertia.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMomentOfInertia.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableMomentOfInertia(double magnitude, double baseUnitMagnitude, MomentOfInertiaUnit unit) implements MomentOfInertia {
|
||||
@Override
|
||||
public MomentOfInertia copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMult.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMult.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableMult<A extends Unit, B extends Unit>(double magnitude, double baseUnitMagnitude, MultUnit<A, B> unit) implements Mult<A, B> {
|
||||
@Override
|
||||
public Mult<A, B> copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePer.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePer.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutablePer<Dividend extends Unit, Divisor extends Unit>(double magnitude, double baseUnitMagnitude, PerUnit<Dividend, Divisor> unit) implements Per<Dividend, Divisor> {
|
||||
@Override
|
||||
public Per<Dividend, Divisor> copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePower.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePower.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutablePower(double magnitude, double baseUnitMagnitude, PowerUnit unit) implements Power {
|
||||
@Override
|
||||
public Power copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTemperature.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTemperature.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableTemperature(double magnitude, double baseUnitMagnitude, TemperatureUnit unit) implements Temperature {
|
||||
@Override
|
||||
public Temperature copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTime.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTime.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableTime(double magnitude, double baseUnitMagnitude, TimeUnit unit) implements Time {
|
||||
@Override
|
||||
public Time copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTorque.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTorque.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableTorque(double magnitude, double baseUnitMagnitude, TorqueUnit unit) implements Torque {
|
||||
@Override
|
||||
public Torque copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVelocity.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVelocity.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableVelocity<D extends Unit>(double magnitude, double baseUnitMagnitude, VelocityUnit<D> unit) implements Velocity<D> {
|
||||
@Override
|
||||
public Velocity<D> copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVoltage.java
generated
Normal file
28
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVoltage.java
generated
Normal file
@@ -0,0 +1,28 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public record ImmutableVoltage(double magnitude, double baseUnitMagnitude, VoltageUnit unit) implements Voltage {
|
||||
@Override
|
||||
public Voltage copy() {
|
||||
return this;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return toShortString();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
return o instanceof Measure<?> m && isEquivalent(m);
|
||||
}
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface LinearAcceleration extends Measure<LinearAccelerationUnit> {
|
||||
static LinearAcceleration ofRelativeUnits(double magnitude, LinearAccelerationUnit unit) {
|
||||
return new ImmutableLinearAcceleration(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static LinearAcceleration ofBaseUnits(double baseUnitMagnitude, LinearAccelerationUnit unit) {
|
||||
return new ImmutableLinearAcceleration(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearAcceleration copy();
|
||||
|
||||
@Override
|
||||
default MutLinearAcceleration mutableCopy() {
|
||||
return new MutLinearAcceleration(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearAccelerationUnit unit();
|
||||
|
||||
@Override
|
||||
default LinearAccelerationUnit baseUnit() { return (LinearAccelerationUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(LinearAccelerationUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration unaryMinus() {
|
||||
return (LinearAcceleration) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration plus(Measure<? extends LinearAccelerationUnit> other) {
|
||||
return (LinearAcceleration) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration minus(Measure<? extends LinearAccelerationUnit> other) {
|
||||
return (LinearAcceleration) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration times(double multiplier) {
|
||||
return (LinearAcceleration) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration divide(double divisor) {
|
||||
return (LinearAcceleration) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<LinearAccelerationUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<LinearAccelerationUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<LinearAccelerationUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<LinearAccelerationUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<LinearAccelerationUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<LinearAccelerationUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<LinearAccelerationUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration divide(Dimensionless divisor) {
|
||||
return (LinearAcceleration) MetersPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration times(Dimensionless multiplier) {
|
||||
return (LinearAcceleration) MetersPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<LinearAccelerationUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<LinearAccelerationUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<LinearAccelerationUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity divide(Frequency divisor) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(LinearAcceleration divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<LinearAccelerationUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<LinearAccelerationUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<LinearAccelerationUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<LinearAccelerationUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<LinearAccelerationUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<LinearAccelerationUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<LinearAccelerationUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<LinearAccelerationUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(Time multiplier) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<LinearAccelerationUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<LinearAccelerationUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<LinearAccelerationUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearAccelerationUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<LinearAccelerationUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearAccelerationUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<LinearAccelerationUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface LinearMomentum extends Measure<LinearMomentumUnit> {
|
||||
static LinearMomentum ofRelativeUnits(double magnitude, LinearMomentumUnit unit) {
|
||||
return new ImmutableLinearMomentum(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static LinearMomentum ofBaseUnits(double baseUnitMagnitude, LinearMomentumUnit unit) {
|
||||
return new ImmutableLinearMomentum(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearMomentum copy();
|
||||
|
||||
@Override
|
||||
default MutLinearMomentum mutableCopy() {
|
||||
return new MutLinearMomentum(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearMomentumUnit unit();
|
||||
|
||||
@Override
|
||||
default LinearMomentumUnit baseUnit() { return (LinearMomentumUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(LinearMomentumUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum unaryMinus() {
|
||||
return (LinearMomentum) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum plus(Measure<? extends LinearMomentumUnit> other) {
|
||||
return (LinearMomentum) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum minus(Measure<? extends LinearMomentumUnit> other) {
|
||||
return (LinearMomentum) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum times(double multiplier) {
|
||||
return (LinearMomentum) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum divide(double divisor) {
|
||||
return (LinearMomentum) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<LinearMomentumUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<LinearMomentumUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<LinearMomentumUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<LinearMomentumUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<LinearMomentumUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<LinearMomentumUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<LinearMomentumUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<LinearMomentumUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<LinearMomentumUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<LinearMomentumUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<LinearMomentumUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<LinearMomentumUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum divide(Dimensionless divisor) {
|
||||
return (LinearMomentum) KilogramMetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearMomentum times(Dimensionless multiplier) {
|
||||
return (LinearMomentum) KilogramMetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<LinearMomentumUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<LinearMomentumUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<LinearMomentumUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<LinearMomentumUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<LinearMomentumUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<LinearMomentumUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Force times(Frequency multiplier) {
|
||||
return Newtons.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<LinearMomentumUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<LinearMomentumUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<LinearMomentumUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<LinearMomentumUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(LinearMomentum divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<LinearMomentumUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass divide(LinearVelocity divisor) {
|
||||
return Kilograms.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<LinearMomentumUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity divide(Mass divisor) {
|
||||
return MetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<LinearMomentumUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<LinearMomentumUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<LinearMomentumUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<LinearMomentumUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<LinearMomentumUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<LinearMomentumUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<LinearMomentumUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<LinearMomentumUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<LinearMomentumUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<LinearMomentumUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<LinearMomentumUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Force divide(Time divisor) {
|
||||
return Newtons.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<LinearMomentumUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<LinearMomentumUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<LinearMomentumUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<LinearMomentumUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearMomentumUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<LinearMomentumUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearMomentumUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<LinearMomentumUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface LinearVelocity extends Measure<LinearVelocityUnit> {
|
||||
static LinearVelocity ofRelativeUnits(double magnitude, LinearVelocityUnit unit) {
|
||||
return new ImmutableLinearVelocity(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static LinearVelocity ofBaseUnits(double baseUnitMagnitude, LinearVelocityUnit unit) {
|
||||
return new ImmutableLinearVelocity(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearVelocity copy();
|
||||
|
||||
@Override
|
||||
default MutLinearVelocity mutableCopy() {
|
||||
return new MutLinearVelocity(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
LinearVelocityUnit unit();
|
||||
|
||||
@Override
|
||||
default LinearVelocityUnit baseUnit() { return (LinearVelocityUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(LinearVelocityUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity unaryMinus() {
|
||||
return (LinearVelocity) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity plus(Measure<? extends LinearVelocityUnit> other) {
|
||||
return (LinearVelocity) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity minus(Measure<? extends LinearVelocityUnit> other) {
|
||||
return (LinearVelocity) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(double multiplier) {
|
||||
return (LinearVelocity) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity divide(double divisor) {
|
||||
return (LinearVelocity) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<LinearVelocityUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<LinearVelocityUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<LinearVelocityUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<LinearVelocityUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<LinearVelocityUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<LinearVelocityUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<LinearVelocityUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<LinearVelocityUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<LinearVelocityUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<LinearVelocityUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<LinearVelocityUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<LinearVelocityUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity divide(Dimensionless divisor) {
|
||||
return (LinearVelocity) MetersPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearVelocity times(Dimensionless multiplier) {
|
||||
return (LinearVelocity) MetersPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<LinearVelocityUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<LinearVelocityUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<LinearVelocityUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<LinearVelocityUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<LinearVelocityUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<LinearVelocityUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default LinearAcceleration times(Frequency multiplier) {
|
||||
return MetersPerSecondPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<LinearVelocityUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<LinearVelocityUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<LinearVelocityUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<LinearVelocityUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<LinearVelocityUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<LinearVelocityUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(LinearVelocity divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<LinearVelocityUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<LinearVelocityUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<LinearVelocityUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<LinearVelocityUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<LinearVelocityUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<LinearVelocityUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<LinearVelocityUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<LinearVelocityUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<LinearVelocityUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<LinearVelocityUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<LinearVelocityUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<LinearVelocityUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Distance times(Time multiplier) {
|
||||
return Meters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default LinearAcceleration divide(Time divisor) {
|
||||
return MetersPerSecondPerSecond.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<LinearVelocityUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<LinearVelocityUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<LinearVelocityUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<LinearVelocityUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<LinearVelocityUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<LinearVelocityUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<LinearVelocityUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<LinearVelocityUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Mass extends Measure<MassUnit> {
|
||||
static Mass ofRelativeUnits(double magnitude, MassUnit unit) {
|
||||
return new ImmutableMass(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static Mass ofBaseUnits(double baseUnitMagnitude, MassUnit unit) {
|
||||
return new ImmutableMass(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Mass copy();
|
||||
|
||||
@Override
|
||||
default MutMass mutableCopy() {
|
||||
return new MutMass(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
MassUnit unit();
|
||||
|
||||
@Override
|
||||
default MassUnit baseUnit() { return (MassUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(MassUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass unaryMinus() {
|
||||
return (Mass) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass plus(Measure<? extends MassUnit> other) {
|
||||
return (Mass) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass minus(Measure<? extends MassUnit> other) {
|
||||
return (Mass) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass times(double multiplier) {
|
||||
return (Mass) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass divide(double divisor) {
|
||||
return (Mass) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MassUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<MassUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<MassUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<MassUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<MassUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<MassUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<MassUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<MassUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<MassUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<MassUnit, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<MassUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<MassUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<MassUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass divide(Dimensionless divisor) {
|
||||
return (Mass) Kilograms.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mass times(Dimensionless multiplier) {
|
||||
return (Mass) Kilograms.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<MassUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<MassUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<MassUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<MassUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<MassUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<MassUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<MassUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<MassUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Force times(LinearAcceleration multiplier) {
|
||||
return Newtons.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<MassUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<MassUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<MassUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<MassUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<MassUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<MassUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(Mass divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<MassUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<MassUnit, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<MassUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<MassUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<MassUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<MassUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<MassUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<MassUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<MassUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<MassUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<MassUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MassUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<MassUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<MassUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<MassUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<MassUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MassUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<MassUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MassUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<MassUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface MomentOfInertia extends Measure<MomentOfInertiaUnit> {
|
||||
static MomentOfInertia ofRelativeUnits(double magnitude, MomentOfInertiaUnit unit) {
|
||||
return new ImmutableMomentOfInertia(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static MomentOfInertia ofBaseUnits(double baseUnitMagnitude, MomentOfInertiaUnit unit) {
|
||||
return new ImmutableMomentOfInertia(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
MomentOfInertia copy();
|
||||
|
||||
@Override
|
||||
default MutMomentOfInertia mutableCopy() {
|
||||
return new MutMomentOfInertia(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
MomentOfInertiaUnit unit();
|
||||
|
||||
@Override
|
||||
default MomentOfInertiaUnit baseUnit() { return (MomentOfInertiaUnit) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(MomentOfInertiaUnit unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia unaryMinus() {
|
||||
return (MomentOfInertia) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia plus(Measure<? extends MomentOfInertiaUnit> other) {
|
||||
return (MomentOfInertia) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia minus(Measure<? extends MomentOfInertiaUnit> other) {
|
||||
return (MomentOfInertia) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia times(double multiplier) {
|
||||
return (MomentOfInertia) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia divide(double divisor) {
|
||||
return (MomentOfInertia) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MomentOfInertiaUnit> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<MomentOfInertiaUnit, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<MomentOfInertiaUnit, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<MomentOfInertiaUnit, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<MomentOfInertiaUnit, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default AngularMomentum times(AngularVelocity multiplier) {
|
||||
return KilogramMetersSquaredPerSecond.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<MomentOfInertiaUnit, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<MomentOfInertiaUnit, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia divide(Dimensionless divisor) {
|
||||
return (MomentOfInertia) KilogramSquareMeters.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default MomentOfInertia times(Dimensionless multiplier) {
|
||||
return (MomentOfInertia) KilogramSquareMeters.of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<MomentOfInertiaUnit, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<MomentOfInertiaUnit, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, ForceUnit> divide(Force divisor) {
|
||||
return (Per<MomentOfInertiaUnit, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<MomentOfInertiaUnit, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<MomentOfInertiaUnit, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<MomentOfInertiaUnit, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<MomentOfInertiaUnit, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, MassUnit> divide(Mass divisor) {
|
||||
return (Per<MomentOfInertiaUnit, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Dimensionless divide(MomentOfInertia divisor) {
|
||||
return Value.of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<MomentOfInertiaUnit, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<MomentOfInertiaUnit, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, PowerUnit> divide(Power divisor) {
|
||||
return (Per<MomentOfInertiaUnit, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<MomentOfInertiaUnit, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MomentOfInertiaUnit> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<MomentOfInertiaUnit, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<MomentOfInertiaUnit, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MomentOfInertiaUnit, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<MomentOfInertiaUnit, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MomentOfInertiaUnit, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<MomentOfInertiaUnit, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java
generated
Normal file
334
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java
generated
Normal file
@@ -0,0 +1,334 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public interface Mult<A extends Unit, B extends Unit> extends Measure<MultUnit<A, B>> {
|
||||
static <A extends Unit, B extends Unit> Mult<A, B> ofRelativeUnits(double magnitude, MultUnit<A, B> unit) {
|
||||
return new ImmutableMult<A, B>(magnitude, unit.toBaseUnits(magnitude), unit);
|
||||
}
|
||||
|
||||
static <A extends Unit, B extends Unit> Mult<A, B> ofBaseUnits(double baseUnitMagnitude, MultUnit<A, B> unit) {
|
||||
return new ImmutableMult<A, B>(unit.fromBaseUnits(baseUnitMagnitude), baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
Mult<A, B> copy();
|
||||
|
||||
@Override
|
||||
default MutMult<A, B> mutableCopy() {
|
||||
return new MutMult<A, B>(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
|
||||
@Override
|
||||
MultUnit<A, B> unit();
|
||||
|
||||
@Override
|
||||
default MultUnit<A, B> baseUnit() { return (MultUnit<A, B>) unit().getBaseUnit(); }
|
||||
|
||||
@Override
|
||||
default double in(MultUnit<A, B> unit) {
|
||||
return unit.fromBaseUnits(baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> unaryMinus() {
|
||||
return (Mult<A, B>) unit().ofBaseUnits(0 - baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> plus(Measure<? extends MultUnit<A, B>> other) {
|
||||
return (Mult<A, B>) unit().ofBaseUnits(baseUnitMagnitude() + other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> minus(Measure<? extends MultUnit<A, B>> other) {
|
||||
return (Mult<A, B>) unit().ofBaseUnits(baseUnitMagnitude() - other.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> times(double multiplier) {
|
||||
return (Mult<A, B>) unit().ofBaseUnits(baseUnitMagnitude() * multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> divide(double divisor) {
|
||||
return (Mult<A, B>) unit().ofBaseUnits(baseUnitMagnitude() / divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MultUnit<A, B>> per(TimeUnit period) {
|
||||
return divide(period.of(1));
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, AccelerationUnit<?>> times(Acceleration<?> multiplier) {
|
||||
return (Mult<MultUnit<A, B>, AccelerationUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, AccelerationUnit<?>> divide(Acceleration<?> divisor) {
|
||||
return (Per<MultUnit<A, B>, AccelerationUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, AngleUnit> times(Angle multiplier) {
|
||||
return (Mult<MultUnit<A, B>, AngleUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, AngleUnit> divide(Angle divisor) {
|
||||
return (Per<MultUnit<A, B>, AngleUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, AngularAccelerationUnit> times(AngularAcceleration multiplier) {
|
||||
return (Mult<MultUnit<A, B>, AngularAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, AngularAccelerationUnit> divide(AngularAcceleration divisor) {
|
||||
return (Per<MultUnit<A, B>, AngularAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, AngularMomentumUnit> times(AngularMomentum multiplier) {
|
||||
return (Mult<MultUnit<A, B>, AngularMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, AngularMomentumUnit> divide(AngularMomentum divisor) {
|
||||
return (Per<MultUnit<A, B>, AngularMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, AngularVelocityUnit> times(AngularVelocity multiplier) {
|
||||
return (Mult<MultUnit<A, B>, AngularVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, AngularVelocityUnit> divide(AngularVelocity divisor) {
|
||||
return (Per<MultUnit<A, B>, AngularVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, CurrentUnit> times(Current multiplier) {
|
||||
return (Mult<MultUnit<A, B>, CurrentUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, CurrentUnit> divide(Current divisor) {
|
||||
return (Per<MultUnit<A, B>, CurrentUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> divide(Dimensionless divisor) {
|
||||
return (Mult<A, B>) unit().of(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
@Override
|
||||
default Mult<A, B> times(Dimensionless multiplier) {
|
||||
return (Mult<A, B>) unit().of(baseUnitMagnitude() * multiplier.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, DistanceUnit> times(Distance multiplier) {
|
||||
return (Mult<MultUnit<A, B>, DistanceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, DistanceUnit> divide(Distance divisor) {
|
||||
return (Per<MultUnit<A, B>, DistanceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, EnergyUnit> times(Energy multiplier) {
|
||||
return (Mult<MultUnit<A, B>, EnergyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, EnergyUnit> divide(Energy divisor) {
|
||||
return (Per<MultUnit<A, B>, EnergyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, ForceUnit> times(Force multiplier) {
|
||||
return (Mult<MultUnit<A, B>, ForceUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, ForceUnit> divide(Force divisor) {
|
||||
return (Per<MultUnit<A, B>, ForceUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, FrequencyUnit> times(Frequency multiplier) {
|
||||
return (Mult<MultUnit<A, B>, FrequencyUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, FrequencyUnit> divide(Frequency divisor) {
|
||||
return (Per<MultUnit<A, B>, FrequencyUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, LinearAccelerationUnit> times(LinearAcceleration multiplier) {
|
||||
return (Mult<MultUnit<A, B>, LinearAccelerationUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, LinearAccelerationUnit> divide(LinearAcceleration divisor) {
|
||||
return (Per<MultUnit<A, B>, LinearAccelerationUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, LinearMomentumUnit> times(LinearMomentum multiplier) {
|
||||
return (Mult<MultUnit<A, B>, LinearMomentumUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, LinearMomentumUnit> divide(LinearMomentum divisor) {
|
||||
return (Per<MultUnit<A, B>, LinearMomentumUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, LinearVelocityUnit> times(LinearVelocity multiplier) {
|
||||
return (Mult<MultUnit<A, B>, LinearVelocityUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, LinearVelocityUnit> divide(LinearVelocity divisor) {
|
||||
return (Per<MultUnit<A, B>, LinearVelocityUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, MassUnit> times(Mass multiplier) {
|
||||
return (Mult<MultUnit<A, B>, MassUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, MassUnit> divide(Mass divisor) {
|
||||
return (Per<MultUnit<A, B>, MassUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, MomentOfInertiaUnit> times(MomentOfInertia multiplier) {
|
||||
return (Mult<MultUnit<A, B>, MomentOfInertiaUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, MomentOfInertiaUnit> divide(MomentOfInertia divisor) {
|
||||
return (Per<MultUnit<A, B>, MomentOfInertiaUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, MultUnit<?, ?>> times(Mult<?, ?> multiplier) {
|
||||
return (Mult<MultUnit<A, B>, MultUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, MultUnit<?, ?>> divide(Mult<?, ?> divisor) {
|
||||
return (Per<MultUnit<A, B>, MultUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, PerUnit<?, ?>> times(Per<?, ?> multiplier) {
|
||||
return (Mult<MultUnit<A, B>, PerUnit<?, ?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, PerUnit<?, ?>> divide(Per<?, ?> divisor) {
|
||||
return (Per<MultUnit<A, B>, PerUnit<?, ?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, PowerUnit> times(Power multiplier) {
|
||||
return (Mult<MultUnit<A, B>, PowerUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, PowerUnit> divide(Power divisor) {
|
||||
return (Per<MultUnit<A, B>, PowerUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, TemperatureUnit> times(Temperature multiplier) {
|
||||
return (Mult<MultUnit<A, B>, TemperatureUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, TemperatureUnit> divide(Temperature divisor) {
|
||||
return (Per<MultUnit<A, B>, TemperatureUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, TimeUnit> times(Time multiplier) {
|
||||
return (Mult<MultUnit<A, B>, TimeUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Velocity<MultUnit<A, B>> divide(Time divisor) {
|
||||
return VelocityUnit.combine(unit(), divisor.unit()).ofBaseUnits(baseUnitMagnitude() / divisor.baseUnitMagnitude());
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, TorqueUnit> times(Torque multiplier) {
|
||||
return (Mult<MultUnit<A, B>, TorqueUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, TorqueUnit> divide(Torque divisor) {
|
||||
return (Per<MultUnit<A, B>, TorqueUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, VelocityUnit<?>> times(Velocity<?> multiplier) {
|
||||
return (Mult<MultUnit<A, B>, VelocityUnit<?>>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, VelocityUnit<?>> divide(Velocity<?> divisor) {
|
||||
return (Per<MultUnit<A, B>, VelocityUnit<?>>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
default Mult<MultUnit<A, B>, VoltageUnit> times(Voltage multiplier) {
|
||||
return (Mult<MultUnit<A, B>, VoltageUnit>) Measure.super.times(multiplier);
|
||||
}
|
||||
|
||||
@Override
|
||||
default Per<MultUnit<A, B>, VoltageUnit> divide(Voltage divisor) {
|
||||
return (Per<MultUnit<A, B>, VoltageUnit>) Measure.super.divide(divisor);
|
||||
}
|
||||
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAcceleration.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAcceleration.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutAcceleration<D extends Unit>
|
||||
extends MutableMeasureBase<AccelerationUnit<D>, Acceleration<D>, MutAcceleration<D>>
|
||||
implements Acceleration<D> {
|
||||
public MutAcceleration(double magnitude, double baseUnitMagnitude, AccelerationUnit<D> unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Acceleration<D> copy() {
|
||||
return new ImmutableAcceleration<D>(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngle.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngle.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutAngle
|
||||
extends MutableMeasureBase<AngleUnit, Angle, MutAngle>
|
||||
implements Angle {
|
||||
public MutAngle(double magnitude, double baseUnitMagnitude, AngleUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Angle copy() {
|
||||
return new ImmutableAngle(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularAcceleration.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularAcceleration.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutAngularAcceleration
|
||||
extends MutableMeasureBase<AngularAccelerationUnit, AngularAcceleration, MutAngularAcceleration>
|
||||
implements AngularAcceleration {
|
||||
public MutAngularAcceleration(double magnitude, double baseUnitMagnitude, AngularAccelerationUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public AngularAcceleration copy() {
|
||||
return new ImmutableAngularAcceleration(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularMomentum.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularMomentum.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutAngularMomentum
|
||||
extends MutableMeasureBase<AngularMomentumUnit, AngularMomentum, MutAngularMomentum>
|
||||
implements AngularMomentum {
|
||||
public MutAngularMomentum(double magnitude, double baseUnitMagnitude, AngularMomentumUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public AngularMomentum copy() {
|
||||
return new ImmutableAngularMomentum(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularVelocity.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularVelocity.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutAngularVelocity
|
||||
extends MutableMeasureBase<AngularVelocityUnit, AngularVelocity, MutAngularVelocity>
|
||||
implements AngularVelocity {
|
||||
public MutAngularVelocity(double magnitude, double baseUnitMagnitude, AngularVelocityUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public AngularVelocity copy() {
|
||||
return new ImmutableAngularVelocity(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutCurrent.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutCurrent.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutCurrent
|
||||
extends MutableMeasureBase<CurrentUnit, Current, MutCurrent>
|
||||
implements Current {
|
||||
public MutCurrent(double magnitude, double baseUnitMagnitude, CurrentUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Current copy() {
|
||||
return new ImmutableCurrent(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDimensionless.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDimensionless.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutDimensionless
|
||||
extends MutableMeasureBase<DimensionlessUnit, Dimensionless, MutDimensionless>
|
||||
implements Dimensionless {
|
||||
public MutDimensionless(double magnitude, double baseUnitMagnitude, DimensionlessUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Dimensionless copy() {
|
||||
return new ImmutableDimensionless(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDistance.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDistance.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutDistance
|
||||
extends MutableMeasureBase<DistanceUnit, Distance, MutDistance>
|
||||
implements Distance {
|
||||
public MutDistance(double magnitude, double baseUnitMagnitude, DistanceUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Distance copy() {
|
||||
return new ImmutableDistance(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutEnergy.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutEnergy.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutEnergy
|
||||
extends MutableMeasureBase<EnergyUnit, Energy, MutEnergy>
|
||||
implements Energy {
|
||||
public MutEnergy(double magnitude, double baseUnitMagnitude, EnergyUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Energy copy() {
|
||||
return new ImmutableEnergy(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutForce.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutForce.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutForce
|
||||
extends MutableMeasureBase<ForceUnit, Force, MutForce>
|
||||
implements Force {
|
||||
public MutForce(double magnitude, double baseUnitMagnitude, ForceUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Force copy() {
|
||||
return new ImmutableForce(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutFrequency.java
generated
Normal file
25
wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutFrequency.java
generated
Normal file
@@ -0,0 +1,25 @@
|
||||
// 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.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpiunits/generate_units.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.units.measure;
|
||||
|
||||
import static edu.wpi.first.units.Units.*;
|
||||
import edu.wpi.first.units.*;
|
||||
import edu.wpi.first.units.mutable.MutableMeasureBase;
|
||||
|
||||
@SuppressWarnings({"unchecked", "cast", "checkstyle", "PMD"})
|
||||
public final class MutFrequency
|
||||
extends MutableMeasureBase<FrequencyUnit, Frequency, MutFrequency>
|
||||
implements Frequency {
|
||||
public MutFrequency(double magnitude, double baseUnitMagnitude, FrequencyUnit unit) {
|
||||
super(magnitude, baseUnitMagnitude, unit);
|
||||
}
|
||||
|
||||
@Override
|
||||
public Frequency copy() {
|
||||
return new ImmutableFrequency(magnitude(), baseUnitMagnitude(), unit());
|
||||
}
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user