Skip to content

Commit 3409be9

Browse files
committed
Merge branch 'feature/talon-config'
2 parents 84d8c38 + 49e0399 commit 3409be9

File tree

6 files changed

+73
-64
lines changed

6 files changed

+73
-64
lines changed

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ dependencies {
4747
testCompile "org.junit.jupiter:junit-jupiter-params:${junit_version}"
4848
testRuntime "org.junit.jupiter:junit-jupiter-engine:${junit_version}"
4949
testCompile "org.assertj:assertj-core:3.11.1"
50-
testCompile 'com.nhaarman.mockitokotlin2:mockito-kotlin:2.0.0'
50+
testCompile "com.nhaarman.mockitokotlin2:mockito-kotlin:2.1.0"
5151

5252
}
5353

gradle.properties

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
kotlin.code.style=official
22
kotlin_version = 1.3.11
33
junit_version = 5.2.0
4-
koin_version = 1.0.1
5-
thirdcoast_version = 19.0.0
4+
koin_version = 1.0.2
5+
thirdcoast_version = 19.1.0

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

Lines changed: 55 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -2,50 +2,85 @@ package org.strykeforce.thirdcoast.device
22

33
import com.ctre.phoenix.motorcontrol.ControlMode
44
import com.ctre.phoenix.motorcontrol.NeutralMode
5+
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
56
import com.ctre.phoenix.motorcontrol.can.TalonSRX
67
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
78
import mu.KotlinLogging
8-
import org.strykeforce.thirdcoast.talon.TalonParameterCommand
99
import org.strykeforce.thirdcoast.talon.SelectFeedbackSensorCommand
10+
import org.strykeforce.thirdcoast.talon.TalonParameterCommand
1011
import org.strykeforce.thirdcoast.telemetry.TelemetryService
1112

1213
private val logger = KotlinLogging.logger {}
1314

15+
private val CONTROL_MODE_DEFAULT = ControlMode.PercentOutput
1416
private const val ACTIVE_SLOT_DEFAULT = 0
15-
private const val VOLTAGE_COMPENSATION_DEFAULT = true
16-
private const val SENSOR_PHASE_DEFAULT = false
17-
private const val CURRENT_LIMIT_DEFAULT = false
18-
private const val INVERTED_DEFAULT = false
17+
private val NEUTRAL_MODE_DEFAULT = NeutralMode.EEPROMSetting
18+
private const val VOLTAGE_COMPENSATION_ENABLED_DEFAULT = true
19+
private const val CURRENT_LIMIT_ENABLED_DEFAULT = false
20+
private const val SENSOR_PHASE_INVERTED_DEFAULT = false
21+
private const val OUTPUT_INVERTED_DEFAULT = false
1922

23+
/**
24+
* Holds the active state for all Talons that have been activated by the user. Talons that are currently active
25+
* can be configured and ran. All Talons that have been made active will be available to the telemetry client (Grapher),
26+
* for the remainder of the `tct` session, even if not currently active.
27+
*
28+
* Persistent configuration settings will be refreshed from the Talon when the `TalonService` is marked as *dirty*. This
29+
* prevents repeated, time-consuming Phoenix API calls to read Talon state.
30+
*
31+
* For non-persistent settings, Talons will be set to a known state when made active. These include:
32+
* - control mode = PercentOutput
33+
* - active slot index = 0
34+
* - brake in neutral mode = EEPROM setting
35+
* - voltage compensation = enabled
36+
* - current limit = enabled
37+
* - sensor phase = not inverted
38+
* - output = not inverted
39+
*
40+
*
41+
* @param telemetryService the telemetry service.
42+
* @param factory a factory lambda expression to instantiate Talons.
43+
*/
2044
class TalonService(private val telemetryService: TelemetryService, factory: (id: Int) -> TalonSRX) :
2145
AbstractDeviceService<TalonSRX>(factory) {
2246

2347
val timeout = 10
48+
var dirty = true
49+
var controlMode = CONTROL_MODE_DEFAULT
2450
var activeSlotIndex: Int = ACTIVE_SLOT_DEFAULT
25-
var controlMode = ControlMode.PercentOutput
26-
var neutralMode = NeutralMode.EEPROMSetting
27-
var voltageCompensation = VOLTAGE_COMPENSATION_DEFAULT
28-
var sensorPhase = SENSOR_PHASE_DEFAULT
29-
var currentLimit = CURRENT_LIMIT_DEFAULT
51+
var neutralMode = NEUTRAL_MODE_DEFAULT
52+
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
53+
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
54+
var currentLimit = CURRENT_LIMIT_ENABLED_DEFAULT
3055

3156
var activeConfiguration = TalonSRXConfiguration()
3257
get() {
58+
if (!dirty) return field
3359
active.firstOrNull()?.getAllConfigs(field) ?: logger.debug("no active talons, returning default config")
60+
dirty = false
3461
return field
3562
}
3663

37-
val outputReverse: Boolean
38-
get() = active.firstOrNull()?.inverted ?: INVERTED_DEFAULT
64+
val activeSlot: SlotConfiguration
65+
get() = when (activeSlotIndex) {
66+
0 -> activeConfiguration.slot0
67+
1 -> activeConfiguration.slot1
68+
2 -> activeConfiguration.slot2
69+
3 -> activeConfiguration.slot3
70+
else -> throw IllegalStateException("invalid slot: $activeSlotIndex")
71+
}
72+
73+
val outputInverted: Boolean
74+
get() = active.firstOrNull()?.inverted ?: OUTPUT_INVERTED_DEFAULT
3975

4076
override fun activate(ids: Collection<Int>) {
41-
TalonParameterCommand.reset = true
42-
SelectFeedbackSensorCommand.reset = true
77+
dirty = true
4378
activeSlotIndex = ACTIVE_SLOT_DEFAULT
44-
controlMode = ControlMode.PercentOutput
45-
neutralMode = NeutralMode.EEPROMSetting
46-
voltageCompensation = VOLTAGE_COMPENSATION_DEFAULT
47-
sensorPhase = SENSOR_PHASE_DEFAULT
48-
currentLimit = CURRENT_LIMIT_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
4984

5085
super.activate(ids)
5186
telemetryService.stop()
@@ -54,7 +89,7 @@ class TalonService(private val telemetryService: TelemetryService, factory: (id:
5489
it.selectProfileSlot(activeSlotIndex, 0)
5590
it.enableVoltageCompensation(voltageCompensation)
5691
it.setSensorPhase(sensorPhase)
57-
it.inverted = INVERTED_DEFAULT
92+
it.inverted = OUTPUT_INVERTED_DEFAULT
5893
it.enableCurrentLimit(currentLimit)
5994
telemetryService.register(it)
6095
}

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

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -37,22 +37,13 @@ class SelectFeedbackSensorCommand(
3737
toml: TomlTable
3838
) : AbstractSelectCommand<FeedbackDevice>(parent, key, toml, SENSORS, LABELS) {
3939

40-
companion object {
41-
var reset = true
42-
}
43-
4440
private val talonService: TalonService by inject()
4541

4642
private val pidIndex = toml.getLong("pid")?.toInt() ?: 0
4743

48-
private var config = talonService.activeConfiguration
49-
5044
override val activeIndex: Int
5145
get() {
52-
if (reset) {
53-
config = talonService.activeConfiguration
54-
reset = false
55-
}
46+
val config = talonService.activeConfiguration
5647

5748
val sensor = when (pidIndex) {
5849
0 -> config.primaryPID.selectedFeedbackSensor
@@ -69,7 +60,12 @@ class SelectFeedbackSensorCommand(
6960
}
7061

7162
override fun setActive(index: Int) {
72-
talonService.active.forEach { it.configSelectedFeedbackSensor(values[index], pidIndex, talonService.timeout) }
73-
reset = true
63+
val sensor = values[index]
64+
talonService.active.forEach { it.configSelectedFeedbackSensor(sensor, pidIndex, talonService.timeout) }
65+
when (pidIndex) {
66+
0 -> talonService.activeConfiguration.primaryPID.selectedFeedbackSensor = sensor
67+
else -> talonService.activeConfiguration.auxiliaryPID.selectedFeedbackSensor = sensor
68+
}
69+
7470
}
7571
}

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,5 @@ class SelectSlotCommand(
2121

2222
override fun setActive(index: Int) {
2323
talonService.activeSlotIndex = index
24-
TalonParameterCommand.reset = true
2524
}
2625
}

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

Lines changed: 7 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,7 @@ package org.strykeforce.thirdcoast.talon
22

33
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced
44
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced.*
5-
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
65
import com.ctre.phoenix.motorcontrol.can.TalonSRX
7-
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
86
import mu.KotlinLogging
97
import net.consensys.cava.toml.TomlTable
108
import org.koin.standalone.inject
@@ -21,19 +19,14 @@ class TalonParameterCommand(
2119
toml: TomlTable
2220
) : AbstractCommand(parent, key, toml) {
2321

24-
companion object {
25-
var reset = true
26-
private var slot: SlotConfiguration = SlotConfiguration()
27-
private var config = TalonSRXConfiguration()
28-
}
29-
3022
private val talonService: TalonService by inject()
3123
private val timeout = talonService.timeout
3224
private val param = TalonParameter.create(this, toml.getString("param") ?: "UNKNOWN")
3325

3426
override val menu: String
3527
get() {
36-
resetConfigIfNeeded()
28+
val config = talonService.activeConfiguration
29+
val slot = talonService.activeSlot
3730
return when (param.enum) {
3831
SLOT_P -> formatMenu(slot.kP)
3932
SLOT_I -> formatMenu(slot.kI)
@@ -43,7 +36,7 @@ class TalonParameterCommand(
4336
SLOT_ALLOWABLE_ERR -> formatMenu(slot.allowableClosedloopError)
4437
SLOT_MAX_I_ACCUM -> formatMenu(slot.maxIntegralAccumulator)
4538
SLOT_PEAK_OUTPUT -> formatMenu(slot.closedLoopPeakOutput)
46-
OUTPUT_REVERSED -> formatMenu(talonService.outputReverse)
39+
OUTPUT_REVERSED -> formatMenu(talonService.outputInverted)
4740
OPEN_LOOP_RAMP -> formatMenu(config.openloopRamp)
4841
CLOSED_LOOP_RAMP -> formatMenu(config.closedloopRamp)
4942
PEAK_OUTPUT_FORWARD -> formatMenu(config.peakOutputForward)
@@ -78,7 +71,9 @@ class TalonParameterCommand(
7871
}
7972

8073
override fun execute(): Command {
81-
resetConfigIfNeeded()
74+
val config = talonService.activeConfiguration
75+
val slot = talonService.activeSlot
76+
8277
when (param.enum) {
8378
SLOT_P -> configDoubleParam(slot.kP) { talon, value ->
8479
talon.config_kP(talonService.activeSlotIndex, value, timeout)
@@ -112,7 +107,7 @@ class TalonParameterCommand(
112107
talon.configClosedLoopPeakOutput(talonService.activeSlotIndex, value, timeout)
113108
slot.closedLoopPeakOutput = value
114109
}
115-
OUTPUT_REVERSED -> configBooleanParam(talonService.outputReverse) { talon, value ->
110+
OUTPUT_REVERSED -> configBooleanParam(talonService.outputInverted) { talon, value ->
116111
talon.inverted = value
117112
}
118113
OPEN_LOOP_RAMP -> configDoubleParam(config.openloopRamp) { talon, value ->
@@ -250,21 +245,5 @@ class TalonParameterCommand(
250245
private fun defaultFor(frame: StatusFrameEnhanced): Int =
251246
talonService.active.first().getStatusFramePeriod(frame)
252247

253-
private fun resetConfigIfNeeded() {
254-
if (reset) {
255-
config = talonService.activeConfiguration
256-
slot = when (talonService.activeSlotIndex) {
257-
0 -> config.slot0
258-
1 -> config.slot1
259-
2 -> config.slot2
260-
3 -> config.slot3
261-
else -> throw IllegalStateException()
262-
}
263-
reset = false
264-
logger.debug { "reset active config to:\n${config.toString("active")}" }
265-
logger.debug { "reset active slot to: \n${slot.toString("active")}" }
266-
}
267-
}
268-
269248
}
270249

0 commit comments

Comments
 (0)