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 33639d9..5666674 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 @@ -348,7 +348,7 @@ inline val DerivativeGain< 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 @@ -548,11 +548,12 @@ inline val ProportionalGain>.inDegreesPerSecondPerFoot: get() = inDegreesPerSecondPerMeter * METERS_PER_FOOT inline val ProportionalGain>.inDegreesPerSecondPerRadian: Double - get() = value + get() = inRadiansPerSecondPerRadian * RADIANS_PER_DEGREES inline val ProportionalGain>.inDegreesPerSecondPerDegree: Double - get() = inDegreesPerSecondPerRadian * RADIANS_PER_DEGREES + get() = inDegreesPerSecondPerRadian / RADIANS_PER_DEGREES +// inline val ProportionalGain>.inDegreesPerSecondPerRotation: Double get() = inDegreesPerSecondPerRadian * RADIANS_PER_ROTATION diff --git a/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/__pycache__/generate.cpython-310.pyc b/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/__pycache__/generate.cpython-310.pyc new file mode 100644 index 0000000..5d75a64 Binary files /dev/null and b/src/main/kotlin/org/team4099/lib/units/derived/controllergeneration/__pycache__/generate.cpython-310.pyc differ 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 dc52848..e095271 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 @@ -11,7 +11,7 @@ def render_template(template_filename, context): return TEMPLATE_ENVIRONMENT.get_template(template_filename).render(context) def create_controller_file(): - fname = "src/main/kotlin/org/team4099/lib/units/derived/Controller.kt" + fname = "../Controller.kt" outputs = ['Volt', 'Ampere', 'Velocity', 'Velocity', "Meter", "Velocity"] output_aliases = ['Volts', 'Amps', 'RadiansPerSecond', "MetersPerSecond", "Meters", "DegreesPerSecond"] context = { diff --git a/src/test/kotlin/team4099/controller/PIDControllerTest.kt b/src/test/kotlin/team4099/controller/PIDControllerTest.kt index 8e37ee1..5f72ffe 100644 --- a/src/test/kotlin/team4099/controller/PIDControllerTest.kt +++ b/src/test/kotlin/team4099/controller/PIDControllerTest.kt @@ -22,7 +22,6 @@ import org.team4099.lib.units.derived.inVoltsPerInch import org.team4099.lib.units.derived.inVoltsPerRotation import org.team4099.lib.units.derived.inVoltsPerRotationPerMinute import org.team4099.lib.units.derived.inVoltsPerRotationsPerMinutePerSecond -import org.team4099.lib.units.derived.metersPerSecondPerMetersPerSecond import org.team4099.lib.units.derived.perInch import org.team4099.lib.units.derived.rotations import org.team4099.lib.units.derived.volts @@ -30,15 +29,6 @@ import org.team4099.lib.units.perMinute import org.team4099.lib.units.perSecond class PIDControllerTest { - - @Test - fun testConstruction() { - val kP: ProportionalGain> = 10.meters.perSecond / 1.meters - val kD = (0.5.meters.perSecond / (1.meters / 1.seconds)).metersPerSecondPerMetersPerSecond - val kI = 0.1.meters.perSecond / (10.meters * 1.seconds) - val positionToVelocityPIDController = PIDController>(kP, kI, kD) - } - @Test fun ampFeedForward() { val aff =