diff --git a/core/src/main/kotlin/org/sert2521/sertain/motors/MotorController.kt b/core/src/main/kotlin/org/sert2521/sertain/motors/MotorController.kt index 9820b8c..a892338 100644 --- a/core/src/main/kotlin/org/sert2521/sertain/motors/MotorController.kt +++ b/core/src/main/kotlin/org/sert2521/sertain/motors/MotorController.kt @@ -44,20 +44,28 @@ class MotorController( } fun eachFollower(configure: MotorController<*>.() -> Unit) { - followers.forEach { it.value.apply(configure) } + followers.forEach { + it.value.apply(configure) + } } fun eachTalon(configure: MotorController.() -> Unit) { eachMotor { @Suppress("unchecked_cast") // Will work because type of id is T - if (id is TalonId) (this as MotorController).apply(configure) + if (id is TalonId) { + (this as MotorController).apply(configure) + Unit + } } } fun eachVictor(configure: MotorController.() -> Unit) { eachMotor { @Suppress("unchecked_cast") // Will work because type of id is T - if (id is VictorId) (this as MotorController).apply(configure) + if (id is VictorId) { + (this as MotorController).apply(configure) + Unit + } } } @@ -244,9 +252,6 @@ class MotorController( } updateCurrentLimit(currentLimit) } - eachMotor { - ctreMotorController.setNeutralMode(ctreNeutralMode(brakeMode)) - } configure() } } diff --git a/core/src/main/kotlin/org/sert2521/sertain/telemetry/TableEntry.kt b/core/src/main/kotlin/org/sert2521/sertain/telemetry/TableEntry.kt index a6c1190..74839cd 100644 --- a/core/src/main/kotlin/org/sert2521/sertain/telemetry/TableEntry.kt +++ b/core/src/main/kotlin/org/sert2521/sertain/telemetry/TableEntry.kt @@ -25,3 +25,5 @@ class TableEntry(val name: String, initialValue: T, val location: List