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 967a352..34b8452 100644 --- a/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt +++ b/src/main/kotlin/org/team4099/lib/units/derived/Controller.kt @@ -3,6 +3,7 @@ package org.team4099.lib.units.derived import org.team4099.lib.units.Fraction import org.team4099.lib.units.Product import org.team4099.lib.units.UnitKey +import org.team4099.lib.units.Unitless import org.team4099.lib.units.Value import org.team4099.lib.units.Velocity import org.team4099.lib.units.base.Ampere @@ -68,6 +69,8 @@ inline val Value.perRadianPerSecond inline val Value.perDegreePerSecond get() = perRadianPerSecond / RADIANS_PER_DEGREES + + inline val Double.VoltsPerVolts get() = Value>(this) @@ -158,6 +161,7 @@ inline val DerivativeGain, Volt>.inVoltsPerDegreesPerSecondPerS inline val DerivativeGain, Volt>.inVoltsPerRotationsPerMinutePerSecond: Double get() = inVoltsPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + inline val Double.AmpsPerAmps get() = Value>(this) @@ -248,6 +252,7 @@ inline val DerivativeGain, Ampere>.inAmpsPerDegreesPerSecondPer inline val DerivativeGain, Ampere>.inAmpsPerRotationsPerMinutePerSecond: Double get() = inAmpsPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + inline val Double.RadiansPerSecondPerRadiansPerSecond get() = Value, Velocity>>(this) @@ -269,16 +274,13 @@ inline val ProportionalGain>.inRadiansPerSecondPerDegre inline val ProportionalGain>.inRadiansPerSecondPerRotation: Double get() = inRadiansPerSecondPerRadian * RADIANS_PER_ROTATION -inline val ProportionalGain, Velocity>.inRadiansPerSecondPerMetersPerSecond: - Double - get() = value +inline val ProportionalGain, Velocity>.inRadiansPerSecondPerMetersPerSecond: Double + get() = value -inline val ProportionalGain< - Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecond: Double +inline val ProportionalGain, Velocity>.inRadiansPerSecondPerRadiansPerSecond: Double get() = value -inline val ProportionalGain< - Velocity, Velocity>.inRadiansPerSecondPerRotationPerMinute: Double +inline val ProportionalGain, Velocity>.inRadiansPerSecondPerRotationPerMinute: Double get() = inRadiansPerSecondPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE inline val IntegralGain>.inRadiansPerSecondPerMeterSeconds: Double @@ -320,8 +322,7 @@ inline val DerivativeGain>.inRadiansPerSecondPerInchPerS inline val DerivativeGain>.inRadiansPerSecondPerFootPerSecond: Double get() = inRadiansPerSecondPerMeterPerSecond * METERS_PER_FOOT -inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerMetersPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inRadiansPerSecondPerMetersPerSecondPerSecond: Double get() = value inline val DerivativeGain>.inRadiansPerSecondPerRadianPerSecond: Double @@ -333,18 +334,16 @@ inline val DerivativeGain>.inRadiansPerSecondPerDegreeP inline val DerivativeGain>.inRadiansPerSecondPerRotationsPerMinute: Double get() = inRadiansPerSecondPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION -inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerRadiansPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inRadiansPerSecondPerRadiansPerSecondPerSecond: Double get() = value -inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerDegreesPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inRadiansPerSecondPerDegreesPerSecondPerSecond: Double get() = inRadiansPerSecondPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES -inline val DerivativeGain< - Velocity, Velocity>.inRadiansPerSecondPerRotationsPerMinutePerSecond: Double +inline val DerivativeGain, Velocity>.inRadiansPerSecondPerRotationsPerMinutePerSecond: Double get() = inRadiansPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + inline val Double.MetersPerSecondPerMetersPerSecond get() = Value, Velocity>>(this) @@ -366,16 +365,13 @@ inline val ProportionalGain>.inMetersPerSecondPerDegree: inline val ProportionalGain>.inMetersPerSecondPerRotation: Double get() = inMetersPerSecondPerRadian * RADIANS_PER_ROTATION -inline val ProportionalGain, Velocity>.inMetersPerSecondPerMetersPerSecond: - Double - get() = value +inline val ProportionalGain, Velocity>.inMetersPerSecondPerMetersPerSecond: Double + get() = value -inline val ProportionalGain, Velocity>.inMetersPerSecondPerRadiansPerSecond: - Double - get() = value +inline val ProportionalGain, Velocity>.inMetersPerSecondPerRadiansPerSecond: Double + get() = value -inline val ProportionalGain< - Velocity, Velocity>.inMetersPerSecondPerRotationPerMinute: Double +inline val ProportionalGain, Velocity>.inMetersPerSecondPerRotationPerMinute: Double get() = inMetersPerSecondPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE inline val IntegralGain>.inMetersPerSecondPerMeterSeconds: Double @@ -417,8 +413,7 @@ inline val DerivativeGain>.inMetersPerSecondPerInchPerSec inline val DerivativeGain>.inMetersPerSecondPerFootPerSecond: Double get() = inMetersPerSecondPerMeterPerSecond * METERS_PER_FOOT -inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerMetersPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inMetersPerSecondPerMetersPerSecondPerSecond: Double get() = value inline val DerivativeGain>.inMetersPerSecondPerRadianPerSecond: Double @@ -430,18 +425,16 @@ inline val DerivativeGain>.inMetersPerSecondPerDegreePer inline val DerivativeGain>.inMetersPerSecondPerRotationsPerMinute: Double get() = inMetersPerSecondPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION -inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerRadiansPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inMetersPerSecondPerRadiansPerSecondPerSecond: Double get() = value -inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerDegreesPerSecondPerSecond: Double +inline val DerivativeGain, Velocity>.inMetersPerSecondPerDegreesPerSecondPerSecond: Double get() = inMetersPerSecondPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES -inline val DerivativeGain< - Velocity, Velocity>.inMetersPerSecondPerRotationsPerMinutePerSecond: Double +inline val DerivativeGain, Velocity>.inMetersPerSecondPerRotationsPerMinutePerSecond: Double get() = inMetersPerSecondPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + inline val Double.MetersPerMeters get() = Value>(this) @@ -531,3 +524,94 @@ inline val DerivativeGain, Meter>.inMetersPerDegreesPerSecondPe inline val DerivativeGain, Meter>.inMetersPerRotationsPerMinutePerSecond: Double get() = inMetersPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + + +inline val Double.DegreesPerDegrees + get() = Value>(this) + +inline val ProportionalGain.inDegreesPerMeter: Double + get() = value + +inline val ProportionalGain.inDegreesPerInch: Double + get() = inDegreesPerMeter * METERS_PER_INCH + +inline val ProportionalGain.inDegreesPerFoot: Double + get() = inDegreesPerMeter * METERS_PER_FOOT + +inline val ProportionalGain.inDegreesPerRadian: Double + get() = value + +inline val ProportionalGain.inDegreesPerDegree: Double + get() = inDegreesPerRadian * RADIANS_PER_DEGREES + +inline val ProportionalGain.inDegreesPerRotation: Double + get() = inDegreesPerRadian * RADIANS_PER_ROTATION + +inline val ProportionalGain, Degrees>.inDegreesPerMetersPerSecond: Double + get() = value + +inline val ProportionalGain, Degrees>.inDegreesPerRadiansPerSecond: Double + get() = value + +inline val ProportionalGain, Degrees>.inDegreesPerRotationPerMinute: Double + get() = inDegreesPerRadiansPerSecond * RADIANS_PER_ROTATION / SECONDS_PER_MINUTE + +inline val IntegralGain.inDegreesPerMeterSeconds: Double + get() = value + +inline val IntegralGain.inDegreesPerInchSeconds: Double + get() = inDegreesPerMeterSeconds * METERS_PER_INCH + +inline val IntegralGain.inDegreesPerFootSeconds: Double + get() = inDegreesPerMeterSeconds * METERS_PER_FOOT + +inline val IntegralGain, Degrees>.inDegreesPerMeters: Double + get() = value + +inline val IntegralGain.inDegreesPerRadianSeconds: Double + get() = value + +inline val IntegralGain.inDegreesPerDegreeSeconds: Double + get() = inDegreesPerRadianSeconds * RADIANS_PER_DEGREES + +inline val IntegralGain.inDegreesPerRotationSeconds: Double + get() = inDegreesPerRadianSeconds / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + +inline val IntegralGain, Degrees>.inDegreesPerRadians: Double + get() = value + +inline val IntegralGain, Degrees>.inDegreesPerDegrees: Double + get() = inDegreesPerRadians * RADIANS_PER_DEGREES + +inline val IntegralGain, Degrees>.inDegreesPerRotations: Double + get() = inDegreesPerRadians / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + +inline val DerivativeGain.inDegreesPerMeterPerSecond: Double + get() = value + +inline val DerivativeGain.inDegreesPerInchPerSecond: Double + get() = inDegreesPerMeterPerSecond * METERS_PER_INCH + +inline val DerivativeGain.inDegreesPerFootPerSecond: Double + get() = inDegreesPerMeterPerSecond * METERS_PER_FOOT + +inline val DerivativeGain, Degrees>.inDegreesPerMetersPerSecondPerSecond: Double + get() = value + +inline val DerivativeGain.inDegreesPerRadianPerSecond: Double + get() = value + +inline val DerivativeGain.inDegreesPerDegreePerSecond: Double + get() = inDegreesPerRadianPerSecond * RADIANS_PER_DEGREES + +inline val DerivativeGain.inDegreesPerRotationsPerMinute: Double + get() = inDegreesPerRadianPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION + +inline val DerivativeGain, Degrees>.inDegreesPerRadiansPerSecondPerSecond: Double + get() = value + +inline val DerivativeGain, Degrees>.inDegreesPerDegreesPerSecondPerSecond: Double + get() = inDegreesPerRadiansPerSecondPerSecond * RADIANS_PER_DEGREES + +inline val DerivativeGain, Degrees>.inDegreesPerRotationsPerMinutePerSecond: Double + get() = inDegreesPerRadiansPerSecondPerSecond / SECONDS_PER_MINUTE * RADIANS_PER_ROTATION diff --git a/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/generate.py b/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/generate.py index 0e8a985..f056e1e 100644 --- a/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/generate.py +++ b/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/generate.py @@ -12,8 +12,8 @@ def render_template(template_filename, context): def create_controller_file(): fname = "src/main/kotlin/org/team4099/lib/units/derived/Controller.kt" - outputs = ['Volt', 'Ampere', 'Velocity', 'Velocity', "Meter"] - output_aliases = ['Volts', 'Amps', 'RadiansPerSecond', "MetersPerSecond", "Meters"] + outputs = ['Volt', 'Ampere', 'Velocity', 'Velocity', "Meter", "Degrees"] + output_aliases = ['Volts', 'Amps', 'RadiansPerSecond', "MetersPerSecond", "Meters", "Degrees"] context = { 'control_outputs': outputs, 'output_aliases': output_aliases,