From 66252e47d012163cbce55c36831c30b1b78f7d85 Mon Sep 17 00:00:00 2001 From: Shom770 Date: Tue, 26 Mar 2024 01:22:50 -0400 Subject: [PATCH] lots of missing constants -- fixed --- build.gradle | 2 +- .../team4099/lib/units/derived/Controller.kt | 57 +++++++++---------- 2 files changed, 29 insertions(+), 30 deletions(-) diff --git a/build.gradle b/build.gradle index ac697a5..2166dda 100644 --- a/build.gradle +++ b/build.gradle @@ -39,7 +39,7 @@ publishing { release(MavenPublication) { groupId = 'org.team4099' artifactId = 'falconutils' - version = '1.1.31r1' + version = '1.1.31r2' from(components["kotlin"]) } diff --git a/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt b/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt index 5666674..326bb5a 100644 --- a/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt +++ b/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt @@ -251,7 +251,7 @@ inline val DerivativeGain, Ampere>.inAmpsPerDegreesPerSecondPer inline val DerivativeGain, Ampere>.inAmpsPerRotationsPerMinutePerSecond: Double get() = inAmpsPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION -inline val Double.RadiansPerSecondPerRadiansPerSecond +inline val Double.radiansPerSecondPerRadiansPerSecond get() = Value, Velocity>>(this) inline val ProportionalGain>.inRadiansPerSecondPerMeter: Double @@ -273,15 +273,15 @@ inline val ProportionalGain>.inRadiansPerSecondPerRotat get() = inRadiansPerSecondPerRadian * RADIANS_PER_ROTATION inline val ProportionalGain, Velocity>.inRadiansPerSecondPerMetersPerSecond: - Double - get() = value + Double + get() = value inline val ProportionalGain< - Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecond: Double + Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecond: Double get() = value inline val ProportionalGain< - Velocity, Velocity>.inRadiansPerSecondPerRotationPerMinute: Double + Velocity, Velocity>.inRadiansPerSecondPerRotationPerMinute: Double get() = inRadiansPerSecondPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE inline val IntegralGain>.inRadiansPerSecondPerMeterSeconds: Double @@ -324,7 +324,7 @@ inline val DerivativeGain>.inRadiansPerSecondPerFootPerS get() = inRadiansPerSecondPerMeterPerSecond * METERS_PER_FOOT inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerMetersPerSecondPerSecond: Double + Velocity, Velocity>.inRadiansPerSecondPerMetersPerSecondPerSecond: Double get() = value inline val DerivativeGain>.inRadiansPerSecondPerRadianPerSecond: Double @@ -337,18 +337,18 @@ inline val DerivativeGain>.inRadiansPerSecondPerRotatio get() = inRadiansPerSecondPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecondPerSecond: Double + Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecondPerSecond: Double get() = value inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerDegreesPerSecondPerSecond: Double + Velocity, Velocity>.inRadiansPerSecondPerDegreesPerSecondPerSecond: Double get() = inRadiansPerSecondPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerRotationsPerMinutePerSecond: Double + Velocity, Velocity>.inRadiansPerSecondPerRotationsPerMinutePerSecond: Double get() = inRadiansPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION -inline val Double.MetersPerSecondPerMetersPerSecond +inline val Double.metersPerSecondPerMetersPerSecond get() = Value, Velocity>>(this) inline val ProportionalGain>.inMetersPerSecondPerMeter: Double @@ -370,15 +370,15 @@ inline val ProportionalGain>.inMetersPerSecondPerRotatio get() = inMetersPerSecondPerRadian * RADIANS_PER_ROTATION inline val ProportionalGain, Velocity>.inMetersPerSecondPerMetersPerSecond: - Double - get() = value + Double + get() = value inline val ProportionalGain, Velocity>.inMetersPerSecondPerRadiansPerSecond: - Double - get() = value + Double + get() = value inline val ProportionalGain< - Velocity, Velocity>.inMetersPerSecondPerRotationPerMinute: Double + Velocity, Velocity>.inMetersPerSecondPerRotationPerMinute: Double get() = inMetersPerSecondPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE inline val IntegralGain>.inMetersPerSecondPerMeterSeconds: Double @@ -421,7 +421,7 @@ inline val DerivativeGain>.inMetersPerSecondPerFootPerSec get() = inMetersPerSecondPerMeterPerSecond * METERS_PER_FOOT inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerMetersPerSecondPerSecond: Double + Velocity, Velocity>.inMetersPerSecondPerMetersPerSecondPerSecond: Double get() = value inline val DerivativeGain>.inMetersPerSecondPerRadianPerSecond: Double @@ -434,15 +434,15 @@ inline val DerivativeGain>.inMetersPerSecondPerRotations get() = inMetersPerSecondPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerRadiansPerSecondPerSecond: Double + Velocity, Velocity>.inMetersPerSecondPerRadiansPerSecondPerSecond: Double get() = value inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerDegreesPerSecondPerSecond: Double + Velocity, Velocity>.inMetersPerSecondPerDegreesPerSecondPerSecond: Double get() = inMetersPerSecondPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerRotationsPerMinutePerSecond: Double + Velocity, Velocity>.inMetersPerSecondPerRotationsPerMinutePerSecond: Double get() = inMetersPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION inline val Double.MetersPerMeters @@ -553,20 +553,19 @@ inline val ProportionalGain>.inDegreesPerSecondPerRadia inline val ProportionalGain>.inDegreesPerSecondPerDegree: Double get() = inDegreesPerSecondPerRadian / RADIANS_PER_DEGREES -// inline val ProportionalGain>.inDegreesPerSecondPerRotation: Double get() = inDegreesPerSecondPerRadian * RADIANS_PER_ROTATION inline val ProportionalGain, Velocity>.inDegreesPerSecondPerMetersPerSecond: - Double - get() = value + Double + get() = value inline val ProportionalGain< - Velocity, Velocity>.inDegreesPerSecondPerRadiansPerSecond: Double + Velocity, Velocity>.inDegreesPerSecondPerRadiansPerSecond: Double get() = value inline val ProportionalGain< - Velocity, Velocity>.inDegreesPerSecondPerRotationPerMinute: Double + Velocity, Velocity>.inDegreesPerSecondPerRotationPerMinute: Double get() = inDegreesPerSecondPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE inline val IntegralGain>.inDegreesPerSecondPerMeterSeconds: Double @@ -609,7 +608,7 @@ inline val DerivativeGain>.inDegreesPerSecondPerFootPerS get() = inDegreesPerSecondPerMeterPerSecond * METERS_PER_FOOT inline val DerivativeGain< - Velocity, Velocity>.inDegreesPerSecondPerMetersPerSecondPerSecond: Double + Velocity, Velocity>.inDegreesPerSecondPerMetersPerSecondPerSecond: Double get() = value inline val DerivativeGain>.inDegreesPerSecondPerRadianPerSecond: Double @@ -622,13 +621,13 @@ inline val DerivativeGain>.inDegreesPerSecondPerRotatio get() = inDegreesPerSecondPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION inline val DerivativeGain< - Velocity, Velocity>.inDegreesPerSecondPerRadiansPerSecondPerSecond: Double + Velocity, Velocity>.inDegreesPerSecondPerRadiansPerSecondPerSecond: Double get() = value inline val DerivativeGain< - Velocity, Velocity>.inDegreesPerSecondPerDegreesPerSecondPerSecond: Double + Velocity, Velocity>.inDegreesPerSecondPerDegreesPerSecondPerSecond: Double get() = inDegreesPerSecondPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES inline val DerivativeGain< - Velocity, Velocity>.inDegreesPerSecondPerRotationsPerMinutePerSecond: Double - get() = inDegreesPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + Velocity, Velocity>.inDegreesPerSecondPerRotationsPerMinutePerSecond: Double + get() = inDegreesPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION \ No newline at end of file