Skip to content

Commit d642d6a

Browse files
committed
Only reset talons that are newly added
Fixes #5
1 parent c4b94e4 commit d642d6a

File tree

7 files changed

+56
-25
lines changed

7 files changed

+56
-25
lines changed

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ fun LineReader.readBoolean(prompt: String = PROMPT, default: Boolean = false) =
5454
}
5555

5656
fun LineReader.readIntList(prompt: String = PROMPT, default: List<Int> = emptyList()): List<Int> = try {
57-
val line = this.readLine(prompt, null, default.joinToString(",")).trim()
57+
val line = this.readLine(prompt, null, default.joinToString()).trim()
5858
if (line.isEmpty()) throw EndOfFileException()
5959
line.split(',').map { it.trim().toInt() }
6060
} catch (e: Exception) {

src/main/kotlin/org/strykeforce/thirdcoast/device/CanifierService.kt

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,11 @@ class CanifierService(private val telemetryService: TelemetryService, factory: (
88
AbstractDeviceService<CANifier>(factory) {
99
val timeout = 10
1010

11-
override fun activate(ids: Collection<Int>) {
12-
super.activate(ids)
11+
override fun activate(ids: Collection<Int>): Set<Int> {
12+
val new = super.activate(ids)
1313
telemetryService.stop()
1414
active.forEach { telemetryService.register(CanifierItem(it)) }
1515
telemetryService.start()
16+
return new
1617
}
1718
}

src/main/kotlin/org/strykeforce/thirdcoast/device/DeviceService.kt

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,19 @@ import mu.KotlinLogging
55
private val logger = KotlinLogging.logger {}
66

77
interface DeviceService<T> {
8+
/** All previously activated devices. */
89
val active: Set<T>
10+
/** Currently active devices. */
911
val all: Set<T>
12+
13+
/** Return a activated device, reusing previously activated devices */
1014
fun get(id: Int): T
11-
fun activate(ids: Collection<Int>)
15+
16+
/** Activate a collection of devices.
17+
* @param ids the ids of devices to activate.
18+
* @return any devices that were added to the currently active set.
19+
*/
20+
fun activate(ids: Collection<Int>): Set<Int>
1221
}
1322

1423
open class AbstractDeviceService<T>(private val factory: (id: Int) -> T) :
@@ -27,9 +36,11 @@ open class AbstractDeviceService<T>(private val factory: (id: Int) -> T) :
2736
return device
2837
}
2938

30-
override fun activate(ids: Collection<Int>) {
39+
override fun activate(ids: Collection<Int>): Set<Int> {
40+
val new = ids.toSet().minus(_active.keys)
3141
_active.clear()
3242
ids.associateTo(_active) { id -> id to get(id) }
43+
return new
3344
}
3445

3546
fun idsInAll(ids: Collection<Int>): Set<Int> = _all.keys.intersect(ids)

src/main/kotlin/org/strykeforce/thirdcoast/device/TalonService.kt

Lines changed: 4 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,6 @@ import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
66
import com.ctre.phoenix.motorcontrol.can.TalonSRX
77
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
88
import mu.KotlinLogging
9-
import org.strykeforce.thirdcoast.talon.SelectFeedbackSensorCommand
10-
import org.strykeforce.thirdcoast.talon.TalonParameterCommand
119
import org.strykeforce.thirdcoast.telemetry.TelemetryService
1210

1311
private val logger = KotlinLogging.logger {}
@@ -73,18 +71,12 @@ class TalonService(private val telemetryService: TelemetryService, factory: (id:
7371
val outputInverted: Boolean
7472
get() = active.firstOrNull()?.inverted ?: OUTPUT_INVERTED_DEFAULT
7573

76-
override fun activate(ids: Collection<Int>) {
74+
override fun activate(ids: Collection<Int>): Set<Int> {
7775
dirty = true
78-
activeSlotIndex = ACTIVE_SLOT_DEFAULT
79-
controlMode = CONTROL_MODE_DEFAULT
80-
neutralMode = NEUTRAL_MODE_DEFAULT
81-
voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
82-
sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
83-
currentLimit = CURRENT_LIMIT_ENABLED_DEFAULT
8476

85-
super.activate(ids)
77+
val new = super.activate(ids)
8678
telemetryService.stop()
87-
active.forEach {
79+
active.filter { new.contains(it.deviceID) }.forEach {
8880
it.setNeutralMode(neutralMode)
8981
it.selectProfileSlot(activeSlotIndex, 0)
9082
it.enableVoltageCompensation(voltageCompensation)
@@ -94,5 +86,6 @@ class TalonService(private val telemetryService: TelemetryService, factory: (id:
9486
telemetryService.register(it)
9587
}
9688
telemetryService.start()
89+
return new
9790
}
9891
}

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

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ import org.strykeforce.thirdcoast.command.AbstractCommand
77
import org.strykeforce.thirdcoast.command.Command
88
import org.strykeforce.thirdcoast.command.prompt
99
import org.strykeforce.thirdcoast.device.TalonService
10+
import org.strykeforce.thirdcoast.info
1011
import org.strykeforce.thirdcoast.readIntList
1112
import org.strykeforce.thirdcoast.warn
1213

@@ -23,13 +24,12 @@ class SelectTalonsCommand(
2324
override fun execute(): Command {
2425
while (true) {
2526
try {
26-
val ids = reader.readIntList(this.prompt("ids"))
27-
val seen = talonService.idsInAll(ids)
28-
talonService.activate(ids)
29-
if (seen.isNotEmpty())
30-
terminal.warn(
27+
val ids = reader.readIntList(this.prompt("ids"), talonService.active.map(TalonSRX::getDeviceID))
28+
val new = talonService.activate(ids)
29+
if (new.isNotEmpty())
30+
terminal.info(
3131
"reset control mode, current limit enabled, brake, voltage compensation\nand sensor phase " +
32-
"for talons: ${seen.joinToString()}"
32+
"for talons: ${new.joinToString()}"
3333
)
3434
return super.execute()
3535
} catch (e: IllegalArgumentException) {

src/test/kotlin/org/strykeforce/thirdcoast/ReadersTest.kt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ internal class ReadersTest {
117117
@Test
118118
fun `read default`() {
119119
val default = listOf(1, 2)
120-
whenever(reader.readLine(any(), isNull(), eq(default.joinToString(","))))
120+
whenever(reader.readLine(any(), isNull(), eq(default.joinToString())))
121121
.thenReturn(" ")
122122
assertThat(reader.readIntList(default = default)).containsExactly(1, 2)
123123
}

src/test/kotlin/org/strykeforce/thirdcoast/device/DeviceServiceTest.kt

Lines changed: 28 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,20 +3,26 @@ package org.strykeforce.thirdcoast.device
33
import com.nhaarman.mockitokotlin2.mock
44
import org.assertj.core.api.Assertions.assertThat
55
import org.junit.jupiter.api.Test
6+
import org.junit.jupiter.api.fail
67

78
internal class DeviceServiceTest {
89

910
@Test
1011
fun `activate adds devices`() {
1112
val stringService = AbstractDeviceService { it.toString() }
1213

13-
stringService.activate(listOf(1, 2, 3, 3))
14+
var new = stringService.activate(listOf(1, 2, 3, 3))
1415
assertThat(stringService.active).containsOnly("1", "2", "3")
1516
assertThat(stringService.all).containsOnly("1", "2", "3")
17+
assertThat(new).containsExactly(1, 2, 3)
1618

17-
stringService.activate(listOf(4, 5, 4, 5))
19+
new = stringService.activate(listOf(4, 5, 4, 5))
1820
assertThat(stringService.active).containsOnly("4", "5")
1921
assertThat(stringService.all).containsOnly("1", "2", "3", "4", "5")
22+
assertThat(new).containsExactly(4, 5)
23+
24+
new = stringService.activate(listOf(1, 2, 3, 4, 5))
25+
assertThat(new).containsExactly(1, 2, 3)
2026
}
2127

2228
@Test
@@ -30,6 +36,26 @@ internal class DeviceServiceTest {
3036
assertThat(stringService.all).containsOnly("1", "2", "3")
3137
}
3238

39+
class TestDevice(val id: Int) {
40+
companion object {
41+
val seen: MutableSet<Int> = mutableSetOf()
42+
}
43+
44+
init {
45+
if (!seen.add(id)) fail { "re-instantiating id: $id" }
46+
}
47+
}
48+
49+
@Test
50+
fun `reactivate seen devices`() {
51+
val testService = AbstractDeviceService { id -> TestDevice(id) }
52+
testService.activate(listOf(1, 2, 3))
53+
assertThat(TestDevice.seen).containsExactly(1, 2, 3)
54+
testService.activate(listOf(1))
55+
testService.activate(listOf(1, 2, 3, 4))
56+
assertThat(TestDevice.seen).containsExactly(1, 2, 3, 4)
57+
}
58+
3359
@Test
3460
fun `service gets same Talon`() {
3561
val talonService = TalonService(mock()) { mock() }

0 commit comments

Comments
 (0)