From a9b885070e2ce9c4226ce0cecaec2f62f442b69e Mon Sep 17 00:00:00 2001 From: Sam Carlberg Date: Sat, 7 Sep 2024 13:59:29 -0400 Subject: [PATCH] [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. --- .github/workflows/pregenerate.yml | 2 + docs/build.gradle | 5 +- .../first/epilogue/EpilogueConfiguration.java | 7 +- .../first/epilogue/logging/DataLogger.java | 2 +- styleguide/checkstyle-suppressions.xml | 2 + .../wpi/first/wpilibj2/command/Command.java | 9 +- .../wpi/first/wpilibj2/command/Commands.java | 5 +- .../command/MecanumControllerCommand.java | 28 +- .../wpilibj2/command/RamseteCommand.java | 16 +- .../first/wpilibj2/command/WaitCommand.java | 9 +- .../wpilibj2/command/sysid/SysIdRoutine.java | 40 +- .../command/sysid/SysIdRoutineTest.java | 5 +- .../edu/wpi/first/wpilibj/LEDPattern.java | 37 +- .../edu/wpi/first/wpilibj/TimedRobot.java | 7 +- .../wpilibj/motorcontrol/MotorController.java | 20 +- .../first/wpilibj/simulation/FlywheelSim.java | 18 +- .../first/wpilibj/sysid/SysIdRoutineLog.java | 30 +- .../edu/wpi/first/wpilibj/LEDPatternTest.java | 2 +- .../examples/addressableled/Robot.java | 5 +- .../examples/sysid/subsystems/Drive.java | 21 +- .../examples/sysid/subsystems/Shooter.java | 21 +- .../controller/SimpleMotorFeedforward.java | 12 +- .../edu/wpi/first/math/geometry/Pose2d.java | 5 +- .../wpi/first/math/geometry/Rotation2d.java | 7 +- .../wpi/first/math/geometry/Transform2d.java | 5 +- .../first/math/geometry/Translation2d.java | 5 +- .../first/math/geometry/Translation3d.java | 5 +- .../first/math/kinematics/ChassisSpeeds.java | 28 +- .../DifferentialDriveKinematics.java | 5 +- .../kinematics/DifferentialDriveOdometry.java | 14 +- .../DifferentialDriveWheelPositions.java | 5 +- .../DifferentialDriveWheelSpeeds.java | 9 +- .../MecanumDriveWheelPositions.java | 8 +- .../kinematics/MecanumDriveWheelSpeeds.java | 14 +- .../kinematics/SwerveDriveKinematics.java | 14 +- .../math/kinematics/SwerveModulePosition.java | 5 +- .../math/kinematics/SwerveModuleState.java | 6 +- .../math/trajectory/TrajectoryConfig.java | 13 +- .../math/trajectory/TrapezoidProfile.java | 12 +- .../SimpleMotorFeedforwardTest.java | 5 +- .../math/kinematics/ChassisSpeedsTest.java | 2 +- .../trajectory/ExponentialProfileTest.java | 5 +- wpiunits/CMakeLists.txt | 6 +- wpiunits/build.gradle | 2 + wpiunits/generate_units.py | 362 +++++++ .../main/java/Measure-immutable.java.jinja | 28 + .../main/java/Measure-interface.java.jinja | 117 +++ .../main/java/Measure-mutable.java.jinja | 25 + .../wpi/first/units/measure/Acceleration.java | 334 ++++++ .../edu/wpi/first/units/measure/Angle.java | 334 ++++++ .../units/measure/AngularAcceleration.java | 334 ++++++ .../first/units/measure/AngularMomentum.java | 334 ++++++ .../first/units/measure/AngularVelocity.java | 334 ++++++ .../edu/wpi/first/units/measure/Current.java | 334 ++++++ .../first/units/measure/Dimensionless.java | 334 ++++++ .../edu/wpi/first/units/measure/Distance.java | 334 ++++++ .../edu/wpi/first/units/measure/Energy.java | 334 ++++++ .../edu/wpi/first/units/measure/Force.java | 334 ++++++ .../wpi/first/units/measure/Frequency.java | 335 ++++++ .../units/measure/ImmutableAcceleration.java | 28 + .../first/units/measure/ImmutableAngle.java | 28 + .../measure/ImmutableAngularAcceleration.java | 28 + .../measure/ImmutableAngularMomentum.java | 28 + .../measure/ImmutableAngularVelocity.java | 28 + .../first/units/measure/ImmutableCurrent.java | 28 + .../units/measure/ImmutableDimensionless.java | 28 + .../units/measure/ImmutableDistance.java | 28 + .../first/units/measure/ImmutableEnergy.java | 28 + .../first/units/measure/ImmutableForce.java | 28 + .../units/measure/ImmutableFrequency.java | 28 + .../measure/ImmutableLinearAcceleration.java | 28 + .../measure/ImmutableLinearMomentum.java | 28 + .../measure/ImmutableLinearVelocity.java | 28 + .../first/units/measure/ImmutableMass.java | 28 + .../measure/ImmutableMomentOfInertia.java | 28 + .../first/units/measure/ImmutableMult.java | 28 + .../wpi/first/units/measure/ImmutablePer.java | 28 + .../first/units/measure/ImmutablePower.java | 28 + .../units/measure/ImmutableTemperature.java | 28 + .../first/units/measure/ImmutableTime.java | 28 + .../first/units/measure/ImmutableTorque.java | 28 + .../units/measure/ImmutableVelocity.java | 28 + .../first/units/measure/ImmutableVoltage.java | 28 + .../units/measure/LinearAcceleration.java | 334 ++++++ .../first/units/measure/LinearMomentum.java | 334 ++++++ .../first/units/measure/LinearVelocity.java | 334 ++++++ .../edu/wpi/first/units/measure/Mass.java | 334 ++++++ .../first/units/measure/MomentOfInertia.java | 334 ++++++ .../edu/wpi/first/units/measure/Mult.java | 334 ++++++ .../first/units/measure/MutAcceleration.java | 25 + .../edu/wpi/first/units/measure/MutAngle.java | 25 + .../units/measure/MutAngularAcceleration.java | 25 + .../units/measure/MutAngularMomentum.java | 25 + .../units/measure/MutAngularVelocity.java | 25 + .../wpi/first/units/measure/MutCurrent.java | 25 + .../first/units/measure/MutDimensionless.java | 25 + .../wpi/first/units/measure/MutDistance.java | 25 + .../wpi/first/units/measure/MutEnergy.java | 25 + .../edu/wpi/first/units/measure/MutForce.java | 25 + .../wpi/first/units/measure/MutFrequency.java | 25 + .../units/measure/MutLinearAcceleration.java | 25 + .../units/measure/MutLinearMomentum.java | 25 + .../units/measure/MutLinearVelocity.java | 25 + .../edu/wpi/first/units/measure/MutMass.java | 25 + .../units/measure/MutMomentOfInertia.java | 25 + .../edu/wpi/first/units/measure/MutMult.java | 25 + .../edu/wpi/first/units/measure/MutPer.java | 25 + .../edu/wpi/first/units/measure/MutPower.java | 25 + .../first/units/measure/MutTemperature.java | 25 + .../edu/wpi/first/units/measure/MutTime.java | 25 + .../wpi/first/units/measure/MutTorque.java | 25 + .../wpi/first/units/measure/MutVelocity.java | 25 + .../wpi/first/units/measure/MutVoltage.java | 25 + .../java/edu/wpi/first/units/measure/Per.java | 341 +++++++ .../edu/wpi/first/units/measure/Power.java | 334 ++++++ .../wpi/first/units/measure/Temperature.java | 334 ++++++ .../edu/wpi/first/units/measure/Time.java | 334 ++++++ .../edu/wpi/first/units/measure/Torque.java | 334 ++++++ .../edu/wpi/first/units/measure/Velocity.java | 334 ++++++ .../edu/wpi/first/units/measure/Voltage.java | 334 ++++++ .../edu/wpi/first/units/AccelerationUnit.java | 113 +++ .../main/java/edu/wpi/first/units/Angle.java | 32 - .../java/edu/wpi/first/units/AngleUnit.java | 93 ++ .../first/units/AngularAccelerationUnit.java | 102 ++ .../wpi/first/units/AngularMomentumUnit.java | 114 +++ .../wpi/first/units/AngularVelocityUnit.java | 101 ++ .../java/edu/wpi/first/units/BaseUnits.java | 23 +- .../wpi/first/units/CombinatoryUnitCache.java | 60 ++ .../java/edu/wpi/first/units/Current.java | 46 - .../java/edu/wpi/first/units/CurrentUnit.java | 105 ++ .../edu/wpi/first/units/Dimensionless.java | 30 - .../wpi/first/units/DimensionlessUnit.java | 99 ++ .../java/edu/wpi/first/units/Distance.java | 29 - .../edu/wpi/first/units/DistanceUnit.java | 102 ++ .../main/java/edu/wpi/first/units/Energy.java | 29 - .../java/edu/wpi/first/units/EnergyUnit.java | 96 ++ .../java/edu/wpi/first/units/ForceUnit.java | 113 +++ .../edu/wpi/first/units/FrequencyUnit.java | 114 +++ .../edu/wpi/first/units/ImmutableMeasure.java | 81 +- .../first/units/LinearAccelerationUnit.java | 125 +++ .../wpi/first/units/LinearMomentumUnit.java | 111 ++ .../wpi/first/units/LinearVelocityUnit.java | 107 ++ .../main/java/edu/wpi/first/units/Mass.java | 30 - .../java/edu/wpi/first/units/MassUnit.java | 112 ++ .../java/edu/wpi/first/units/Measure.java | 954 ++++++++++++++++-- .../wpi/first/units/MomentOfInertiaUnit.java | 107 ++ .../main/java/edu/wpi/first/units/Mult.java | 123 --- .../java/edu/wpi/first/units/MultUnit.java | 229 +++++ .../edu/wpi/first/units/MutableMeasure.java | 228 +---- .../main/java/edu/wpi/first/units/Per.java | 140 --- .../java/edu/wpi/first/units/PerUnit.java | 287 ++++++ .../main/java/edu/wpi/first/units/Power.java | 29 - .../java/edu/wpi/first/units/PowerUnit.java | 164 +++ .../java/edu/wpi/first/units/Temperature.java | 25 - .../edu/wpi/first/units/TemperatureUnit.java | 86 ++ .../main/java/edu/wpi/first/units/Time.java | 29 - .../java/edu/wpi/first/units/TimeUnit.java | 102 ++ .../java/edu/wpi/first/units/TorqueUnit.java | 101 ++ .../main/java/edu/wpi/first/units/Unit.java | 222 ++-- .../java/edu/wpi/first/units/UnitBuilder.java | 14 +- .../main/java/edu/wpi/first/units/Units.java | 336 ++++-- .../java/edu/wpi/first/units/Velocity.java | 188 ---- .../edu/wpi/first/units/VelocityUnit.java | 140 +++ .../java/edu/wpi/first/units/Voltage.java | 46 - .../java/edu/wpi/first/units/VoltageUnit.java | 105 ++ .../mutable/GenericMutableMeasureImpl.java | 79 ++ .../units/mutable/MutableMeasureBase.java | 86 ++ ...{CurrentTest.java => CurrentUnitTest.java} | 14 +- ...istanceTest.java => DistanceUnitTest.java} | 8 +- .../java/edu/wpi/first/units/EncoderTest.java | 91 -- .../java/edu/wpi/first/units/ExampleUnit.java | 28 +- .../java/edu/wpi/first/units/MeasureTest.java | 241 ++--- .../{MultTest.java => MultUnitTest.java} | 10 +- .../wpi/first/units/MutableMeasureTest.java | 133 --- .../java/edu/wpi/first/units/PerUnitTest.java | 56 + .../java/edu/wpi/first/units/UnitsTest.java | 39 +- ...elocityTest.java => VelocityUnitTest.java} | 19 +- ...{VoltageTest.java => VoltageUnitTest.java} | 7 +- 178 files changed, 14668 insertions(+), 2076 deletions(-) create mode 100755 wpiunits/generate_units.py create mode 100644 wpiunits/src/generate/main/java/Measure-immutable.java.jinja create mode 100644 wpiunits/src/generate/main/java/Measure-interface.java.jinja create mode 100644 wpiunits/src/generate/main/java/Measure-mutable.java.jinja create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Acceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Angle.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/AngularVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Current.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Dimensionless.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Distance.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Energy.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Force.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Frequency.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngle.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableAngularVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableCurrent.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDimensionless.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableDistance.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableEnergy.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableForce.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableFrequency.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableLinearVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMass.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMomentOfInertia.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableMult.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePer.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutablePower.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTemperature.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTime.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableTorque.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/ImmutableVoltage.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/LinearVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mass.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MomentOfInertia.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Mult.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngle.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutAngularVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutCurrent.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDimensionless.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutDistance.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutEnergy.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutForce.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutFrequency.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutLinearAcceleration.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutLinearMomentum.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutLinearVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutMass.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutMomentOfInertia.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutMult.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutPer.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutPower.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutTemperature.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutTime.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutTorque.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutVelocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/MutVoltage.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Per.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Power.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Temperature.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Time.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Torque.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Velocity.java create mode 100644 wpiunits/src/generated/main/java/edu/wpi/first/units/measure/Voltage.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/AccelerationUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Angle.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/AngleUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/AngularAccelerationUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/AngularMomentumUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/AngularVelocityUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/CombinatoryUnitCache.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Current.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/CurrentUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Dimensionless.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/DimensionlessUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Distance.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/DistanceUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Energy.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/EnergyUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/ForceUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/FrequencyUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/LinearAccelerationUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/LinearMomentumUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/LinearVelocityUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Mass.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/MassUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/MomentOfInertiaUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Mult.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/MultUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Per.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/PerUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Power.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/PowerUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Temperature.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/TemperatureUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Time.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/TimeUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/TorqueUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Velocity.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/VelocityUnit.java delete mode 100644 wpiunits/src/main/java/edu/wpi/first/units/Voltage.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/VoltageUnit.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/mutable/GenericMutableMeasureImpl.java create mode 100644 wpiunits/src/main/java/edu/wpi/first/units/mutable/MutableMeasureBase.java rename wpiunits/src/test/java/edu/wpi/first/units/{CurrentTest.java => CurrentUnitTest.java} (52%) rename wpiunits/src/test/java/edu/wpi/first/units/{DistanceTest.java => DistanceUnitTest.java} (83%) delete mode 100644 wpiunits/src/test/java/edu/wpi/first/units/EncoderTest.java rename wpiunits/src/test/java/edu/wpi/first/units/{MultTest.java => MultUnitTest.java} (80%) delete mode 100644 wpiunits/src/test/java/edu/wpi/first/units/MutableMeasureTest.java create mode 100644 wpiunits/src/test/java/edu/wpi/first/units/PerUnitTest.java rename wpiunits/src/test/java/edu/wpi/first/units/{VelocityTest.java => VelocityUnitTest.java} (72%) rename wpiunits/src/test/java/edu/wpi/first/units/{VoltageTest.java => VoltageUnitTest.java} (67%) diff --git a/.github/workflows/pregenerate.yml b/.github/workflows/pregenerate.yml index f356b087140..decca974b6c 100644 --- a/.github/workflows/pregenerate.yml +++ b/.github/workflows/pregenerate.yml @@ -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 diff --git a/docs/build.gradle b/docs/build.gradle index 526bae0c7bb..4104c6db874 100644 --- a/docs/build.gradle +++ b/docs/build.gradle @@ -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) diff --git a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java index 868a7cb0bf6..84bdc1fae5d 100644 --- a/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java +++ b/epilogue-runtime/src/main/java/edu/wpi/first/epilogue/EpilogueConfiguration.java @@ -9,8 +9,7 @@ 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