Skip to content

Commit

Permalink
inline value and mechanism sensors
Browse files Browse the repository at this point in the history
  • Loading branch information
sswadkar committed Jan 22, 2023
1 parent b8e4a1a commit fe60d70
Show file tree
Hide file tree
Showing 3 changed files with 54 additions and 48 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ publishing {
release(MavenPublication) {
groupId = 'org.team4099'
artifactId = 'falconutils'
version = '1.1.0'
version = '1.1.1'

from(components["kotlin"])
}
Expand Down
70 changes: 37 additions & 33 deletions src/main/kotlin/org/team4099/lib/units/MechanismUnits.kt
Original file line number Diff line number Diff line change
Expand Up @@ -72,44 +72,45 @@ interface MechanismSensor<U : UnitKey> {
}

class LinearMechanismSensor(
private val diameter: Length,
private val ratio: Double,
private val timescale: Timescale,
private val fullPowerThrottle: Double,
private val compensationVoltage: ElectricalPotential,
val diameter: Length,
val ratio: Double,
val timescale: Timescale,
val fullPowerThrottle: Double,
val compensationVoltage: ElectricalPotential,
val getRawVelocity: () -> Double,
val getRawPosition: () -> Double
) : MechanismSensor<Meter> {
override val position: Length
override inline val position: Length
get() = (diameter * PI) * getRawPosition() * ratio

override val velocity: Value<Velocity<Meter>>
override inline val velocity: Value<Velocity<Meter>>
get() {
val linearUnscaledVelocity = diameter.inMeters * getRawVelocity() * ratio * PI
return (linearUnscaledVelocity / timescale.velocity.inSeconds).meters.perSecond
}

override fun positionToRawUnits(position: Value<Meter>): Double = position / diameter / ratio / PI
override inline fun positionToRawUnits(position: Value<Meter>): Double =
position / diameter / ratio / PI

override fun velocityToRawUnits(velocity: Value<Velocity<Meter>>): Double {
override inline fun velocityToRawUnits(velocity: Value<Velocity<Meter>>): Double {
val linearUnscaledVelocity = velocity.inMetersPerSecond * timescale.velocity.inSeconds
return linearUnscaledVelocity / diameter.inMeters / ratio / PI
}

override fun accelerationToRawUnits(acceleration: Value<Acceleration<Meter>>): Double {
override inline fun accelerationToRawUnits(acceleration: Value<Acceleration<Meter>>): Double {
val linearUnscaledVelocity =
velocity.inMetersPerSecond * timescale.velocity.inSeconds * timescale.acceleration.inSeconds
return linearUnscaledVelocity / diameter.inMeters / ratio / PI
}

override fun proportionalPositionGainToRawUnits(
override inline fun proportionalPositionGainToRawUnits(
proportionalGain: ProportionalGain<Meter, Volt>
): Double {
return (proportionalGain.inVoltsPerMeter / (positionToRawUnits(1.meters))) /
compensationVoltage.inVolts * fullPowerThrottle
}

override fun integralPositionGainToRawUnits(
override inline fun integralPositionGainToRawUnits(
integralGain: IntegralGain<Meter, Volt>,
): Double {
return (
Expand All @@ -119,7 +120,7 @@ class LinearMechanismSensor(
compensationVoltage.inVolts * fullPowerThrottle
}

override fun derivativePositionGainToRawUnits(
override inline fun derivativePositionGainToRawUnits(
derivativeGain: DerivativeGain<Meter, Volt>,
): Double {
return (
Expand All @@ -128,14 +129,14 @@ class LinearMechanismSensor(
) / compensationVoltage.inVolts * fullPowerThrottle
}

override fun proportionalVelocityGainToRawUnits(
override inline fun proportionalVelocityGainToRawUnits(
proportionalGain: ProportionalGain<Velocity<Meter>, Volt>
): Double {
return (proportionalGain.inVoltsPerMetersPerSecond / (velocityToRawUnits(1.meters.perSecond))) /
compensationVoltage.inVolts * fullPowerThrottle
}

override fun integralVelocityGainToRawUnits(
override inline fun integralVelocityGainToRawUnits(
integralGain: IntegralGain<Velocity<Meter>, Volt>,
): Double {
return (
Expand All @@ -145,7 +146,7 @@ class LinearMechanismSensor(
compensationVoltage.inVolts * fullPowerThrottle
}

override fun derivativeVelocityGainToRawUnits(
override inline fun derivativeVelocityGainToRawUnits(
derivativeGain: DerivativeGain<Velocity<Meter>, Volt>,
): Double {
return (
Expand All @@ -154,7 +155,7 @@ class LinearMechanismSensor(
) / compensationVoltage.inVolts * fullPowerThrottle
}

override fun velocityFeedforwardToRawUnits(
override inline fun velocityFeedforwardToRawUnits(
velocityFeedforward: VelocityFeedforward<Meter, Volt>
): Double {
return velocityFeedforward.value * velocityToRawUnits(1.0.meters.perSecond) /
Expand All @@ -163,47 +164,50 @@ class LinearMechanismSensor(
}

class AngularMechanismSensor(
private val ratio: Double,
private val timescale: Timescale,
private val fullPowerThrottle: Double,
private val compensationVoltage: ElectricalPotential,
val ratio: Double,
val timescale: Timescale,
val fullPowerThrottle: Double,
val compensationVoltage: ElectricalPotential,
val getRawVelocity: () -> Double,
val getRawPosition: () -> Double
) : MechanismSensor<Radian> {
override val position: Value<Radian>
override inline val position: Value<Radian>
get() = (getRawPosition() * ratio).rotations

override val velocity: Value<Velocity<Radian>>
override inline val velocity: Value<Velocity<Radian>>
get() = (getRawVelocity() * ratio / timescale.velocity.inSeconds).rotations.perSecond

override fun positionToRawUnits(position: Value<Radian>): Double = position.inRotations / ratio
override inline fun positionToRawUnits(position: Value<Radian>): Double =
position.inRotations / ratio

override fun velocityToRawUnits(velocity: Value<Velocity<Radian>>): Double =
override inline fun velocityToRawUnits(velocity: Value<Velocity<Radian>>): Double =
(velocity.inRotationsPerSecond * timescale.velocity.inSeconds) / ratio

override fun accelerationToRawUnits(acceleration: Value<Acceleration<Radian>>): Double =
override inline fun accelerationToRawUnits(acceleration: Value<Acceleration<Radian>>): Double =
(
acceleration.inRotationsPerSecondPerSecond *
timescale.velocity.inSeconds *
timescale.acceleration.inSeconds
) / ratio

override fun proportionalPositionGainToRawUnits(
override inline fun proportionalPositionGainToRawUnits(
proportionalGain: ProportionalGain<Radian, Volt>
): Double {
return (proportionalGain.inVoltsPerRadian / (positionToRawUnits(1.radians))) /
compensationVoltage.inVolts * fullPowerThrottle
}

override fun integralPositionGainToRawUnits(integralGain: IntegralGain<Radian, Volt>): Double {
override inline fun integralPositionGainToRawUnits(
integralGain: IntegralGain<Radian, Volt>
): Double {
return (
integralGain.inVoltsPerRadianSeconds /
(positionToRawUnits(1.radians) * timescale.velocity.inSeconds)
) /
compensationVoltage.inVolts * fullPowerThrottle
}

override fun derivativePositionGainToRawUnits(
override inline fun derivativePositionGainToRawUnits(
derivativeGain: DerivativeGain<Radian, Volt>
): Double {
return (
Expand All @@ -212,7 +216,7 @@ class AngularMechanismSensor(
) / compensationVoltage.inVolts * fullPowerThrottle
}

override fun proportionalVelocityGainToRawUnits(
override inline fun proportionalVelocityGainToRawUnits(
proportionalGain: ProportionalGain<Velocity<Radian>, Volt>
): Double {
return (
Expand All @@ -221,7 +225,7 @@ class AngularMechanismSensor(
) / compensationVoltage.inVolts * fullPowerThrottle
}

override fun integralVelocityGainToRawUnits(
override inline fun integralVelocityGainToRawUnits(
integralGain: IntegralGain<Velocity<Radian>, Volt>
): Double {
return (
Expand All @@ -231,7 +235,7 @@ class AngularMechanismSensor(
compensationVoltage.inVolts * fullPowerThrottle
}

override fun derivativeVelocityGainToRawUnits(
override inline fun derivativeVelocityGainToRawUnits(
derivativeGain: DerivativeGain<Velocity<Radian>, Volt>
): Double {
return (
Expand All @@ -240,7 +244,7 @@ class AngularMechanismSensor(
) / compensationVoltage.inVolts * fullPowerThrottle
}

override fun velocityFeedforwardToRawUnits(
override inline fun velocityFeedforwardToRawUnits(
velocityFeedforward: VelocityFeedforward<Radian, Volt>
): Double {
return velocityFeedforward.value * velocityToRawUnits(1.0.radians.perSecond) /
Expand Down
30 changes: 16 additions & 14 deletions src/main/kotlin/org/team4099/lib/units/Value.kt
Original file line number Diff line number Diff line change
Expand Up @@ -5,31 +5,33 @@ import kotlin.math.sign

@JvmInline
value class Value<T : UnitKey>(val value: Double) : Comparable<Value<T>> {
val absoluteValue: Value<T>
inline val absoluteValue: Value<T>
get() = Value(value.absoluteValue)

val sign: Double
inline val sign: Double
get() = sign(value)

operator fun plus(o: Value<T>): Value<T> = Value(value + o.value)
operator fun minus(o: Value<T>): Value<T> = Value(value - o.value)
inline operator fun plus(o: Value<T>): Value<T> = Value(value + o.value)
inline operator fun minus(o: Value<T>): Value<T> = Value(value - o.value)

operator fun times(k: Double): Value<T> = Value(value * k)
operator fun times(k: Number): Value<T> = this * k.toDouble()
operator fun <K : UnitKey> times(o: Value<Fraction<K, T>>): Value<K> = Value(value * o.value)
inline operator fun times(k: Double): Value<T> = Value(value * k)
inline operator fun times(k: Number): Value<T> = this * k.toDouble()
inline operator fun <K : UnitKey> times(o: Value<Fraction<K, T>>): Value<K> =
Value(value * o.value)

@Suppress("INAPPLICABLE_JVM_NAME")
@JvmName("times1")
operator fun <K : UnitKey> times(o: Value<K>): Value<Product<T, K>> = Value(value * o.value)
inline operator fun <K : UnitKey> times(o: Value<K>): Value<Product<T, K>> =
Value(value * o.value)

operator fun unaryMinus(): Value<T> = Value(-value)
inline operator fun unaryMinus(): Value<T> = Value(-value)

operator fun div(k: Double): Value<T> = Value(value / k)
operator fun div(k: Number): Value<T> = this / k.toDouble()
operator fun div(o: Value<T>): Double = value / o.value
operator fun <K : UnitKey> div(o: Value<K>): Value<Fraction<T, K>> = Value(value / o.value)
inline operator fun div(k: Double): Value<T> = Value(value / k)
inline operator fun div(k: Number): Value<T> = this / k.toDouble()
inline operator fun div(o: Value<T>): Double = value / o.value
inline operator fun <K : UnitKey> div(o: Value<K>): Value<Fraction<T, K>> = Value(value / o.value)

override operator fun compareTo(other: Value<T>): Int = value.compareTo(other.value)
override inline operator fun compareTo(other: Value<T>): Int = value.compareTo(other.value)
}

infix fun <T : UnitKey> ClosedRange<Value<T>>.step(step: Value<T>): Iterable<Value<T>> {
Expand Down

0 comments on commit fe60d70

Please sign in to comment.