From 5b2ff9f0aa06e9fd545fe8a07947553c2e857dbb Mon Sep 17 00:00:00 2001 From: DanielRocksUrMom <108989218+DanielRocksUrMom@users.noreply.github.com> Date: Tue, 9 Jan 2024 16:22:28 -0500 Subject: [PATCH] Unit updates --- build.gradle | 2 +- .../builddata/ChargerLibBuildConstants.java | 10 +++++----- .../EncoderDifferentialDrivetrain.kt | 6 ++++-- .../swervedrive/EncoderHolonomicDrivetrain.kt | 4 +--- .../utils/math/units/FeedforwardUnits.kt | 11 ++++++---- .../chargers/utils/math/units/Operations.kt | 20 ------------------- .../frc/chargers/utils/math/units/Rem.kt | 12 +++++++++++ 7 files changed, 30 insertions(+), 35 deletions(-) delete mode 100644 src/main/kotlin/frc/chargers/utils/math/units/Operations.kt create mode 100644 src/main/kotlin/frc/chargers/utils/math/units/Rem.kt diff --git a/build.gradle b/build.gradle index d6acb1a9..0d60642a 100644 --- a/build.gradle +++ b/build.gradle @@ -43,7 +43,7 @@ configurations.configureEach { kotlin { explicitApi() - //jvmToolchain(17) + //jvmToolchain(21) compileKotlin { compilerOptions { diff --git a/src/main/java/frc/chargerlibexternal/builddata/ChargerLibBuildConstants.java b/src/main/java/frc/chargerlibexternal/builddata/ChargerLibBuildConstants.java index e0fb602d..bef7c127 100644 --- a/src/main/java/frc/chargerlibexternal/builddata/ChargerLibBuildConstants.java +++ b/src/main/java/frc/chargerlibexternal/builddata/ChargerLibBuildConstants.java @@ -7,12 +7,12 @@ public final class ChargerLibBuildConstants { public static final String MAVEN_GROUP = "frc.chargers"; public static final String MAVEN_NAME = "ChargerLib"; public static final String VERSION = "1.0.0"; - public static final int GIT_REVISION = 260; - public static final String GIT_SHA = "d05f31b80fc224b4c9522cbbd9c14e0bacb362b9"; - public static final String GIT_DATE = "2024-01-07T18:34:00Z"; + public static final int GIT_REVISION = 261; + public static final String GIT_SHA = "dc1da73de4a09c1eae729551160a95126f179563"; + public static final String GIT_DATE = "2024-01-09T12:51:49Z"; public static final String GIT_BRANCH = "master"; - public static final String BUILD_DATE = "2024-01-07T20:26:19Z"; - public static final long BUILD_UNIX_TIME = 1704677179102L; + public static final String BUILD_DATE = "2024-01-09T13:45:32Z"; + public static final long BUILD_UNIX_TIME = 1704825932597L; public static final int DIRTY = 1; private ChargerLibBuildConstants(){} diff --git a/src/main/kotlin/frc/chargers/hardware/subsystems/differentialdrive/EncoderDifferentialDrivetrain.kt b/src/main/kotlin/frc/chargers/hardware/subsystems/differentialdrive/EncoderDifferentialDrivetrain.kt index de0358a8..04d469aa 100644 --- a/src/main/kotlin/frc/chargers/hardware/subsystems/differentialdrive/EncoderDifferentialDrivetrain.kt +++ b/src/main/kotlin/frc/chargers/hardware/subsystems/differentialdrive/EncoderDifferentialDrivetrain.kt @@ -132,7 +132,8 @@ public class EncoderDifferentialDrivetrain( getInput = {leftVelocity}, target = AngularVelocity(0.0), setpointSupplier = SetpointSupplier.Default( - feedforward = Feedforward(controlData.leftFF) + // leftFF stores the left feedforward constants. + Feedforward(controlData.leftFF) ), selfSustain = true, ) @@ -142,7 +143,8 @@ public class EncoderDifferentialDrivetrain( getInput = {rightVelocity}, target = AngularVelocity(0.0), setpointSupplier = SetpointSupplier.Default( - feedforward = Feedforward(controlData.rightFF) + // rightff stores the right feedforward constants. + Feedforward(controlData.rightFF) ), selfSustain = true, ) diff --git a/src/main/kotlin/frc/chargers/hardware/subsystems/swervedrive/EncoderHolonomicDrivetrain.kt b/src/main/kotlin/frc/chargers/hardware/subsystems/swervedrive/EncoderHolonomicDrivetrain.kt index befd9247..1640f34c 100644 --- a/src/main/kotlin/frc/chargers/hardware/subsystems/swervedrive/EncoderHolonomicDrivetrain.kt +++ b/src/main/kotlin/frc/chargers/hardware/subsystems/swervedrive/EncoderHolonomicDrivetrain.kt @@ -24,8 +24,6 @@ import frc.chargers.hardware.subsystems.swervedrive.module.* import frc.chargers.hardware.subsystems.swervedrive.module.lowlevel.* import frc.chargers.pathplannerextensions.asPathPlannerConstants import frc.chargers.utils.math.inputModulus -import frc.chargers.utils.math.units.pow -import frc.chargers.utils.math.units.sqrt import frc.chargers.wpilibextensions.geometry.ofUnit import frc.chargers.wpilibextensions.geometry.twodimensional.UnitPose2d import frc.chargers.wpilibextensions.geometry.twodimensional.UnitTranslation2d @@ -338,7 +336,7 @@ public class EncoderHolonomicDrivetrain( */ public val velocity: Velocity get(){ val speeds = currentSpeeds - return sqrt(speeds.xVelocity.pow(2.0) + speeds.yVelocity.pow(2.0)) + return hypot(speeds.xVelocity, speeds.yVelocity) } diff --git a/src/main/kotlin/frc/chargers/utils/math/units/FeedforwardUnits.kt b/src/main/kotlin/frc/chargers/utils/math/units/FeedforwardUnits.kt index 9f5acb77..26a021e2 100644 --- a/src/main/kotlin/frc/chargers/utils/math/units/FeedforwardUnits.kt +++ b/src/main/kotlin/frc/chargers/utils/math/units/FeedforwardUnits.kt @@ -12,22 +12,22 @@ import kotlin.internal.LowPriorityInOverloadResolution /** * Represents a kV gain for an angular velocity targeting feedforward. */ -public typealias VoltagePerAngularVelocity = Quantity +public typealias VoltagePerAngularVelocity = KmeasureUnit /** * Represents a kV gain for a linear velocity targeting feedforward. */ -public typealias VoltagePerVelocity = Quantity +public typealias VoltagePerVelocity = KmeasureUnit /** * Represents a kA gain for an angular velocity targeting feedforward. */ -public typealias VoltagePerAngularAcceleration = Quantity +public typealias VoltagePerAngularAcceleration = KmeasureUnit /** * Represents a kA gain for a linear velocity targeting feedforward. */ -public typealias VoltagePerAcceleration = Quantity +public typealias VoltagePerAcceleration = KmeasureUnit public typealias VoltagePerAngularVelocityDimension = MagneticFluxDimension @@ -39,6 +39,9 @@ public typealias VoltagePerAngularAccelerationDimension = Dimension + + + @JvmName("KvMultipliedAngular") @LowPriorityInOverloadResolution public operator fun VoltagePerAngularVelocity.times(other: Time): VoltagePerAngularAcceleration = diff --git a/src/main/kotlin/frc/chargers/utils/math/units/Operations.kt b/src/main/kotlin/frc/chargers/utils/math/units/Operations.kt deleted file mode 100644 index 7d5c9161..00000000 --- a/src/main/kotlin/frc/chargers/utils/math/units/Operations.kt +++ /dev/null @@ -1,20 +0,0 @@ -package frc.chargers.utils.math.units - -import com.batterystaple.kmeasure.dimensions.* -import com.batterystaple.kmeasure.interop.transformWithSIValue -import com.batterystaple.kmeasure.quantities.* -import kotlin.math.pow - - -public operator fun Quantity.rem(other: Quantity): Quantity = - Quantity(siValue % other.siValue) - -public fun Quantity.pow(exponent: Number): Quantity = - transformWithSIValue{it.pow(exponent.toDouble())} - -public fun sqrt(value: Quantity): Quantity = - Quantity(kotlin.math.sqrt(value.siValue)) - - - - diff --git a/src/main/kotlin/frc/chargers/utils/math/units/Rem.kt b/src/main/kotlin/frc/chargers/utils/math/units/Rem.kt new file mode 100644 index 00000000..cac5926d --- /dev/null +++ b/src/main/kotlin/frc/chargers/utils/math/units/Rem.kt @@ -0,0 +1,12 @@ +package frc.chargers.utils.math.units + +import com.batterystaple.kmeasure.dimensions.* +import com.batterystaple.kmeasure.quantities.* + + +public operator fun Quantity.rem(other: Quantity): Quantity = + Quantity(siValue % other.siValue) + + + +