Skip to content

Commit 00d758a

Browse files
authored
Merge pull request #15 from strykeforce/mwitcpalek/talonFX
Mwitcpalek/talon fx
2 parents 97b2776 + bb4e898 commit 00d758a

31 files changed

+1958
-189
lines changed

build.gradle

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@ plugins {
44
id "edu.wpi.first.GradleRIO" version "2020.1.2"
55
}
66

7+
version = "20.0.0"
8+
79
sourceCompatibility = JavaVersion.VERSION_11
810
targetCompatibility = JavaVersion.VERSION_11
911

@@ -94,7 +96,7 @@ jar {
9496
manifest {
9597
attributes(
9698
'Implementation-Title': 'Third Coast Telemetry Utility (tct)',
97-
'Implementation-Version': '20.0.0'
99+
'Implementation-Version': version
98100
)
99101
}
100102
}

gradle.properties

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
kotlin.code.style=official
Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
1+
#Sat Jan 18 13:27:09 EST 2020
2+
distributionUrl=https\://services.gradle.org/distributions/gradle-6.0.1-all.zip
13
distributionBase=GRADLE_USER_HOME
24
distributionPath=permwrapper/dists
3-
distributionUrl=https\://services.gradle.org/distributions/gradle-6.0.1-bin.zip
4-
zipStoreBase=GRADLE_USER_HOME
55
zipStorePath=permwrapper/dists
6+
zipStoreBase=GRADLE_USER_HOME

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,10 @@ package org.strykeforce.thirdcoast
33
import com.ctre.phoenix.CANifier
44
import com.ctre.phoenix.motorcontrol.FeedbackDevice
55
import com.ctre.phoenix.motorcontrol.NeutralMode
6+
import com.ctre.phoenix.motorcontrol.can.TalonFX
67
import com.ctre.phoenix.motorcontrol.can.TalonSRX
78
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
9+
import com.ctre.phoenix.sensors.PigeonIMU
810
import edu.wpi.first.wpilibj.DigitalOutput
911
import edu.wpi.first.wpilibj.Servo
1012
import edu.wpi.first.wpilibj.Solenoid
@@ -34,6 +36,8 @@ val tctModule = module {
3436
single { TelemetryService(Function { inventory -> TelemetryController(inventory, get(), SERVER_PORT) }) }
3537

3638
single { TalonService(get()) { id -> TalonSRX(id) } }
39+
40+
single { TalonFxService(get()) { id -> TalonFX(id) } }
3741

3842
single { ServoService { id -> Servo(id) } }
3943

@@ -43,6 +47,8 @@ val tctModule = module {
4347

4448
single { CanifierService(get()) { id -> CANifier(id) } }
4549

50+
single { PigeonService(get()) { id -> PigeonIMU(id) } }
51+
4652
single { (command: Command) -> Shell(command, get()) }
4753

4854
single<Terminal> { TerminalBuilder.terminal() }

src/main/kotlin/org/strykeforce/thirdcoast/command/Command.kt

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
package org.strykeforce.thirdcoast.command
22

3+
import mu.KotlinLogging
34
import net.consensys.cava.toml.TomlTable
45
import org.jline.reader.LineReader
56
import org.jline.terminal.Terminal
@@ -10,6 +11,8 @@ import org.koin.standalone.inject
1011
import org.strykeforce.thirdcoast.canifier.*
1112
import org.strykeforce.thirdcoast.dio.RunDigitalOutputsCommand
1213
import org.strykeforce.thirdcoast.dio.SelectDigitalOutputsCommand
14+
import org.strykeforce.thirdcoast.gyro.PigeonParameterCommand
15+
import org.strykeforce.thirdcoast.gyro.SelectPigeonCommand
1316
import org.strykeforce.thirdcoast.servo.RunServosCommand
1417
import org.strykeforce.thirdcoast.servo.SelectServosCommand
1518
import org.strykeforce.thirdcoast.solenoid.RunSolenoidsCommand
@@ -20,7 +23,7 @@ import org.strykeforce.thirdcoast.swerve.SelectAzimuthCommand
2023
import org.strykeforce.thirdcoast.swerve.SetAzimuthCommand
2124
import org.strykeforce.thirdcoast.talon.*
2225

23-
//private val logger = KotlinLogging.logger {}
26+
private val logger = KotlinLogging.logger {}
2427

2528
interface Command {
2629
val key: String
@@ -34,10 +37,12 @@ interface Command {
3437
const val MENU_KEY = "menu"
3538
const val TYPE_KEY = "type"
3639
const val ORDER_KEY = "order"
40+
const val DEVICE_KEY = "device"
3741

3842
fun createFromToml(toml: TomlTable, parent: MenuCommand? = null, key: String = "ROOT"): Command {
3943

4044
val type = toml.getString(TYPE_KEY) ?: throw Exception("$key: $TYPE_KEY missing")
45+
logger.info { "type: $type, key: $key" }
4146

4247
return when (type) {
4348
"menu" -> createMenuCommand(parent, key, toml)
@@ -54,6 +59,9 @@ interface Command {
5459
"talon.hard.source" -> SelectHardLimitSourceCommand(parent, key, toml)
5560
"talon.hard.normal" -> SelectHardLimitNormalCommand(parent, key, toml)
5661
"talon.velocity.period" -> SelectVelocityMeasurmentPeriodCommand(parent, key, toml)
62+
"talon.commutation" -> SelectMotorCommutationCommand(parent, key, toml)
63+
"talon.absoluteRange" -> SelectAbsoluteSensorRange(parent, key, toml)
64+
"talon.initStrategy" -> SelectInitializationStrategy(parent, key, toml)
5765
"servo.select" -> SelectServosCommand(parent, key, toml)
5866
"servo.run" -> RunServosCommand(parent, key, toml)
5967
"solenoid.select" -> SelectSolenoidsCommand(parent, key, toml)
@@ -71,6 +79,8 @@ interface Command {
7179
"swerve.azimuth.save" -> SaveZeroCommand(parent, key, toml)
7280
"swerve.azimuth.select" -> SelectAzimuthCommand(parent, key, toml)
7381
"swerve.azimuth.adjust" -> AdjustAzimuthCommand(parent, key, toml)
82+
"pigeon.select" -> SelectPigeonCommand(parent, key, toml)
83+
"pigeon.param" -> PigeonParameterCommand(parent, key, toml)
7484
else -> DefaultCommand(parent, key, toml)
7585
}
7686
}
@@ -81,6 +91,7 @@ interface Command {
8191
.forEach { k ->
8292
val child = createFromToml(toml.getTable(k)!!, command, k)
8393
command.children.add(child)
94+
logger.info { "Create Menu: $k, ${command.validMenuChoices}" }
8495
}
8596
return command
8697
}
Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
package org.strykeforce.thirdcoast.device
2+
3+
import com.ctre.phoenix.sensors.PigeonIMU
4+
import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame
5+
import org.strykeforce.thirdcoast.telemetry.item.PigeonIMUItem
6+
import mu.KotlinLogging
7+
import org.strykeforce.thirdcoast.telemetry.TelemetryService
8+
9+
private val logger = KotlinLogging.logger {}
10+
11+
private const val DEFAULT_TEMP_COMP = false
12+
13+
14+
class PigeonService(private val telemetryService: TelemetryService, factory: (id: Int) -> PigeonIMU) :
15+
AbstractDeviceService<PigeonIMU>(factory) {
16+
17+
val timeout = 10
18+
var tempCompensation = DEFAULT_TEMP_COMP
19+
20+
21+
override fun activate(ids: Collection<Int>): Set<Int> {
22+
val new = super.activate(ids)
23+
telemetryService.stop()
24+
active.forEach {telemetryService.register(PigeonIMUItem(it)) }
25+
active.forEach {
26+
it.setTemperatureCompensationDisable(tempCompensation)
27+
}
28+
29+
telemetryService.start()
30+
return new
31+
}
32+
33+
}
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
package org.strykeforce.thirdcoast.device
2+
3+
import com.ctre.phoenix.motorcontrol.ControlMode
4+
import com.ctre.phoenix.motorcontrol.NeutralMode
5+
import com.ctre.phoenix.motorcontrol.StatusFrame
6+
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced
7+
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
8+
import com.ctre.phoenix.motorcontrol.can.TalonFX
9+
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration
10+
import mu.KotlinLogging
11+
import org.strykeforce.thirdcoast.telemetry.TelemetryService
12+
import java.lang.IllegalStateException
13+
import kotlin.math.log
14+
15+
private val logger = KotlinLogging.logger {}
16+
17+
private val CONTROL_MODE_DEFAULT = ControlMode.PercentOutput
18+
private const val ACTIVE_SLOT_DEFAULT = 0
19+
private val NEUTRAL_MODE_DEFAULT = NeutralMode.EEPROMSetting
20+
private const val VOLTAGE_COMPENSATION_ENABLED_DEFAULT = true
21+
private const val CURRENT_LIMIT_ENABLED_DEFAULT = false
22+
private const val SENSOR_PHASE_INVERTED_DEFAULT = false
23+
private const val OUTPUT_INVERTED_DEFAULT = false
24+
25+
26+
class TalonFxService(private val telemetryService: TelemetryService, factory: (id:Int) -> TalonFX ):
27+
AbstractDeviceService<TalonFX>(factory) {
28+
29+
val timeout = 10
30+
var dirty = true
31+
var neutralMode = NEUTRAL_MODE_DEFAULT
32+
var controlMode = CONTROL_MODE_DEFAULT
33+
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
34+
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
35+
var activeSlotIndex: Int = ACTIVE_SLOT_DEFAULT
36+
37+
var activeConfiguration = TalonFXConfiguration()
38+
get() {
39+
if(!dirty) return field
40+
active.firstOrNull()?.getAllConfigs(field,timeout)?: logger.debug("no active talon fx's, returning default config")
41+
dirty = false
42+
return field
43+
}
44+
45+
val activeSlot: SlotConfiguration
46+
get() = when(activeSlotIndex){
47+
0 -> activeConfiguration.slot0
48+
1 -> activeConfiguration.slot1
49+
2 -> activeConfiguration.slot2
50+
3 -> activeConfiguration.slot3
51+
else -> throw IllegalStateException("invalid slot: $activeSlotIndex")
52+
}
53+
54+
val outputInverted: Boolean
55+
get() = active.firstOrNull()?.inverted?: OUTPUT_INVERTED_DEFAULT
56+
57+
override fun activate(ids: Collection<Int>): Set<Int> {
58+
dirty = true
59+
60+
val new = super.activate(ids)
61+
telemetryService.stop()
62+
active.filter { new.contains(it.deviceID) }.forEach(){
63+
it.setNeutralMode(neutralMode)
64+
it.selectProfileSlot(activeSlotIndex,0)
65+
it.enableVoltageCompensation(voltageCompensation)
66+
it.setSensorPhase(sensorPhase)
67+
it.setInverted(OUTPUT_INVERTED_DEFAULT)
68+
telemetryService.register(it)
69+
}
70+
telemetryService.start()
71+
return new
72+
}
73+
}

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

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@ 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.SupplyCurrentLimitConfiguration
56
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
67
import com.ctre.phoenix.motorcontrol.can.TalonSRX
78
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
@@ -17,6 +18,10 @@ private const val VOLTAGE_COMPENSATION_ENABLED_DEFAULT = true
1718
private const val CURRENT_LIMIT_ENABLED_DEFAULT = false
1819
private const val SENSOR_PHASE_INVERTED_DEFAULT = false
1920
private const val OUTPUT_INVERTED_DEFAULT = false
21+
private const val SUPPLY_CURRENT_LIMIT_ENABLE_DEFAULT = false
22+
private const val SUPPLY_CURRENT_LIMIT_DEFAULT = 0.0
23+
private const val SUPPLY_CURRENT_LIMIT_TRIG_CURRENT_DEFAULT = 0.0
24+
private const val SUPPLY_CURRENT_LIMIT_TRIG_TIME_DEFAULT = 0.0
2025

2126
/**
2227
* Holds the active state for all Talons that have been activated by the user. Talons that are currently active
@@ -50,6 +55,7 @@ class TalonService(private val telemetryService: TelemetryService, factory: (id:
5055
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
5156
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
5257
var currentLimit = CURRENT_LIMIT_ENABLED_DEFAULT
58+
var supplyCurrentLimit = SupplyCurrentLimitConfiguration(SUPPLY_CURRENT_LIMIT_ENABLE_DEFAULT, SUPPLY_CURRENT_LIMIT_DEFAULT, SUPPLY_CURRENT_LIMIT_TRIG_CURRENT_DEFAULT, SUPPLY_CURRENT_LIMIT_TRIG_TIME_DEFAULT)
5359

5460
var activeConfiguration = TalonSRXConfiguration()
5561
get() {
Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
package org.strykeforce.thirdcoast.gyro
2+
3+
import net.consensys.cava.toml.TomlTable
4+
import org.strykeforce.thirdcoast.command.AbstractParameter
5+
import org.strykeforce.thirdcoast.command.Command
6+
import org.strykeforce.thirdcoast.parseResource
7+
import org.strykeforce.thirdcoast.talon.TalonParameter
8+
9+
class PigeonParameter(command: Command, toml: TomlTable, val enum: PigeonParameter.Enum) : AbstractParameter(command, toml) {
10+
11+
enum class Enum {
12+
ACCUM_Z_ANGLE,
13+
FUSED_HEADING,
14+
TEMP_COMP_DISABLE,
15+
YAW,
16+
GENERAL_STATUS,
17+
SIX_DEG_STATUS,
18+
FUSED_STATUS,
19+
GYRO_ACCUM_STATUS,
20+
GEN_COMPASS_STATUS,
21+
GEN_ACCEL_STATUS,
22+
SIX_QUAT_STATUS,
23+
MAG_STATUS,
24+
BIAS_GYRO_STATUS,
25+
BIAS_MAG_STATUS,
26+
BIAS_ACCEL_STATUS,
27+
FACTORY_DEFAULT,
28+
}
29+
30+
companion object {
31+
private val tomlTable by lazy { parseResource("/pigeon.toml") }
32+
33+
fun create(command: Command, param: String): PigeonParameter {
34+
val toml = tomlTable.getTable(param) ?: throw java.lang.IllegalArgumentException("missing param: $param")
35+
return PigeonParameter(command, toml, Enum.valueOf(param))
36+
}
37+
}
38+
}

0 commit comments

Comments
 (0)