Skip to content

Commit 3237a70

Browse files
committed
Update dependencies for FRC 2021
1 parent ca9b154 commit 3237a70

File tree

11 files changed

+168
-125
lines changed

11 files changed

+168
-125
lines changed

build.gradle

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,10 @@
11
plugins {
22
id "java"
3-
id "org.jetbrains.kotlin.jvm" version "1.3.61"
4-
id "edu.wpi.first.GradleRIO" version "2020.1.2"
3+
id "org.jetbrains.kotlin.jvm" version "1.4.21"
4+
id "edu.wpi.first.GradleRIO" version "2021.2.1"
55
}
66

7-
version = "20.0.1"
7+
version = "21.0.0"
88

99
sourceCompatibility = JavaVersion.VERSION_11
1010
targetCompatibility = JavaVersion.VERSION_11
@@ -87,6 +87,10 @@ dependencies {
8787
simulation wpi.deps.sim.gui(wpi.platforms.desktop, false)
8888
}
8989

90+
test {
91+
useJUnitPlatform()
92+
}
93+
9094
// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar')
9195
// in order to make them all available at runtime. Also adding the manifest so WPILib
9296
// knows where to look for our Robot Class.

src/main/kotlin/org/strykeforce/thirdcoast/Koin.kt

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -80,11 +80,11 @@ private fun getWheels(): Array<Wheel> {
8080
kI = 0.0
8181
kD = 100.0
8282
kF = 1.0
83-
integralZone = 0
84-
allowableClosedloopError = 0
83+
integralZone = 0.0
84+
allowableClosedloopError = 0.0
8585
}
86-
motionAcceleration = 10_000
87-
motionCruiseVelocity = 800
86+
motionAcceleration = 10_000.0
87+
motionCruiseVelocity = 800.0
8888
}
8989

9090

src/main/kotlin/org/strykeforce/thirdcoast/swerve/AdjustAzimuthCommands.kt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ class AdjustAzimuthCommand(
5353

5454
override fun execute(): Command {
5555
val wheel = swerve.wheels[active]
56-
var position = wheel.azimuthTalon.getSelectedSensorPosition(0)
56+
var position = wheel.azimuthTalon.getSelectedSensorPosition(0).toInt()
5757
while (true) {
5858
try {
5959
position = reader.readInt(prompt(), position)

src/main/kotlin/org/strykeforce/thirdcoast/talon/HardLimitCommands.kt

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -41,10 +41,11 @@ class SelectHardLimitSourceCommand(
4141

4242
override val activeIndex: Int
4343
get() {
44-
var config: BaseTalonConfiguration
45-
if(type == "srx") config = talonService.activeConfiguration
46-
else if(type == "fx") config = talonFxService.activeConfiguration
47-
else throw IllegalArgumentException()
44+
var config: BaseTalonConfiguration = when (type) {
45+
"srx" -> talonService.activeConfiguration
46+
"fx" -> talonFxService.activeConfiguration
47+
else -> throw IllegalArgumentException()
48+
}
4849
return values.indexOf(
4950
if (isForward)
5051
config.forwardLimitSwitchSource

src/main/kotlin/org/strykeforce/thirdcoast/talon/SetSensorPositionCommand.kt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,11 +35,11 @@ class SetSensorPositionCommand(
3535

3636
val paramValue = param.readInt(reader, default)
3737
if(type == "srx") {
38-
talonService.active.forEach { it.setSelectedSensorPosition(paramValue, pidIndex, timeout) }
38+
talonService.active.forEach { it.setSelectedSensorPosition(paramValue.toDouble(), pidIndex, timeout) }
3939
logger.debug { "set ${talonService.active.size} talon ${param.name}: $paramValue" }
4040
}
4141
else if(type == "fx") {
42-
talonFxService.active.forEach { it.setSelectedSensorPosition(paramValue, pidIndex, talonFxService.timeout) }
42+
talonFxService.active.forEach { it.setSelectedSensorPosition(paramValue.toDouble(), pidIndex, talonFxService.timeout) }
4343
logger.debug { "set ${talonFxService.active.size} talonfx ${param.name}: $paramValue" }
4444
}
4545
return super.execute()

src/main/kotlin/org/strykeforce/thirdcoast/talon/TalonParameterCommand.kt

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -173,13 +173,13 @@ class TalonParameterCommand(
173173
baseTalon.config_kF(activeSlotIndex, value, timeout)
174174
slot.kF = value
175175
}
176-
SLOT_I_ZONE -> configIntParam(slot.integralZone) { baseTalon, value ->
177-
baseTalon.config_IntegralZone(activeSlotIndex, value, timeout)
178-
slot.integralZone = value
176+
SLOT_I_ZONE -> configIntParam(slot.integralZone.toInt()) { baseTalon, value ->
177+
baseTalon.config_IntegralZone(activeSlotIndex, value.toDouble(), timeout)
178+
slot.integralZone = value.toDouble()
179179
}
180-
SLOT_ALLOWABLE_ERR -> configIntParam(slot.allowableClosedloopError) { baseTalon, value ->
181-
baseTalon.configAllowableClosedloopError(activeSlotIndex, value, timeout)
182-
slot.allowableClosedloopError = value
180+
SLOT_ALLOWABLE_ERR -> configIntParam(slot.allowableClosedloopError.toInt()) { baseTalon, value ->
181+
baseTalon.configAllowableClosedloopError(activeSlotIndex, value.toDouble(), timeout)
182+
slot.allowableClosedloopError = value.toDouble()
183183
}
184184
SLOT_MAX_I_ACCUM -> configDoubleParam(slot.maxIntegralAccumulator) { baseTalon, value ->
185185
baseTalon.configMaxIntegralAccumulator(activeSlotIndex, value, timeout)
@@ -236,13 +236,13 @@ class TalonParameterCommand(
236236
baseTalon.configVoltageMeasurementFilter(value, timeout)
237237
config.voltageMeasurementFilter = value
238238
}
239-
MOTION_CRUISE_VELOCITY -> configIntParam(config.motionCruiseVelocity) { baseTalon, value ->
240-
baseTalon.configMotionCruiseVelocity(value, timeout)
241-
config.motionCruiseVelocity = value
239+
MOTION_CRUISE_VELOCITY -> configIntParam(config.motionCruiseVelocity.toInt()) { baseTalon, value ->
240+
baseTalon.configMotionCruiseVelocity(value.toDouble(), timeout)
241+
config.motionCruiseVelocity = value.toDouble()
242242
}
243-
MOTION_ACCELERATION -> configIntParam(config.motionAcceleration) { baseTalon, value ->
244-
baseTalon.configMotionAcceleration(value, timeout)
245-
config.motionAcceleration = value
243+
MOTION_ACCELERATION -> configIntParam(config.motionAcceleration.toInt()) { baseTalon, value ->
244+
baseTalon.configMotionAcceleration(value.toDouble(), timeout)
245+
config.motionAcceleration = value.toDouble()
246246
}
247247
SENSOR_PHASE -> configBooleanParam(talonService.sensorPhase) { baseTalon, value ->
248248
baseTalon.setSensorPhase(value)
@@ -386,13 +386,13 @@ class TalonParameterCommand(
386386
baseTalon.configReverseSoftLimitEnable(value, timeout)
387387
config.reverseSoftLimitEnable = value
388388
}
389-
SOFT_LIMIT_THRESHOLD_FORWARD -> configIntParam(config.forwardSoftLimitThreshold) { baseTalon, value ->
390-
baseTalon.configForwardSoftLimitThreshold(value, timeout)
391-
config.forwardSoftLimitThreshold = value
389+
SOFT_LIMIT_THRESHOLD_FORWARD -> configIntParam(config.forwardSoftLimitThreshold.toInt()) { baseTalon, value ->
390+
baseTalon.configForwardSoftLimitThreshold(value.toDouble(), timeout)
391+
config.forwardSoftLimitThreshold = value.toDouble()
392392
}
393-
SOFT_LIMIT_THRESHOLD_REVERSE -> configIntParam(config.reverseSoftLimitThreshold) { baseTalon, value ->
394-
baseTalon.configReverseSoftLimitThreshold(value, timeout)
395-
config.reverseSoftLimitThreshold = value
393+
SOFT_LIMIT_THRESHOLD_REVERSE -> configIntParam(config.reverseSoftLimitThreshold.toInt()) { baseTalon, value ->
394+
baseTalon.configReverseSoftLimitThreshold(value.toDouble(), timeout)
395+
config.reverseSoftLimitThreshold = value.toDouble()
396396
}
397397
VELOCITY_MEASUREMENT_WINDOW -> configIntParam(config.velocityMeasurementWindow) { baseTalon, value ->
398398
baseTalon.configVelocityMeasurementWindow(value, timeout)

src/test/kotlin/org/strykeforce/thirdcoast/talon/HardLimitCommandsTest.kt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,15 +24,18 @@ internal class HardLimitCommandsTest : KoinTest {
2424
type = "menu"
2525
[limit]
2626
type = "menu"
27+
device = "srx"
2728
order = 1
2829
menu = "configure soft and hard limits"
2930
[limit.forward_hard_source]
3031
type = "talon.hard.source"
32+
device = "srx"
3133
order = 1
3234
forward = true
3335
menu = "forward hard limit switch source"
3436
[limit.forward_hard_normal]
3537
type = "talon.hard.normal"
38+
device = "srx"
3639
order = 2
3740
forward = true
3841
menu = "forward hard limit switch normal"

src/test/kotlin/org/strykeforce/thirdcoast/talon/TalonParameterCommandTest.kt

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ internal class TalonParameterCommandTest : KoinTest {
4747
@Test
4848
fun `param is parsed`() {
4949
val toml = """
50+
device = "srx"
5051
name = "P"
5152
param = "SLOT_P"
5253
""".trimIndent()
@@ -93,10 +94,10 @@ internal class TalonParameterCommandTest : KoinTest {
9394
@Test
9495
fun `config IZone`() {
9596
val talonService: TalonService by inject()
96-
val command = TalonParameterCommand(parent, "foo", Toml.parse("param=\"SLOT_I_ZONE\""))
97+
val command = TalonParameterCommand(parent, "foo", Toml.parse("device = \"srx\"\nparam=\"SLOT_I_ZONE\""))
9798
talonService.activate(listOf(1))
9899
command.execute()
99-
verify(talon).config_IntegralZone(0, 27, 10)
100+
verify(talon).config_IntegralZone(0, 27.0, 10)
100101
}
101102

102103
@Test
@@ -105,7 +106,7 @@ internal class TalonParameterCommandTest : KoinTest {
105106
val command = TalonParameterCommand(parent, "foo", Toml.parse("param=\"SLOT_ALLOWABLE_ERR\""))
106107
talonService.activate(listOf(1))
107108
command.execute()
108-
verify(talon).configAllowableClosedloopError(0, 27, 10)
109+
verify(talon).configAllowableClosedloopError(0, 27.0, 10)
109110
}
110111

111112
@Test

0 commit comments

Comments
 (0)