Skip to content

Commit 5246fa1

Browse files
committed
Update for 2022 dependencies
1 parent 70c1561 commit 5246fa1

File tree

12 files changed

+226
-131
lines changed

12 files changed

+226
-131
lines changed

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

Lines changed: 34 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ import com.ctre.phoenix.motorcontrol.can.TalonFX
77
import com.ctre.phoenix.motorcontrol.can.TalonSRX
88
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
99
import com.ctre.phoenix.sensors.PigeonIMU
10+
import edu.wpi.first.math.geometry.Translation2d
1011
import edu.wpi.first.wpilibj.DigitalOutput
1112
import edu.wpi.first.wpilibj.PneumaticsModuleType
1213
import edu.wpi.first.wpilibj.Servo
@@ -16,15 +17,14 @@ import org.jline.reader.LineReaderBuilder
1617
import org.jline.terminal.Terminal
1718
import org.jline.terminal.TerminalBuilder
1819
import org.koin.dsl.module.module
20+
import org.strykeforce.swerve.*
1921
import org.strykeforce.thirdcoast.command.Command
2022
import org.strykeforce.thirdcoast.device.*
21-
import org.strykeforce.thirdcoast.swerve.SwerveDrive
22-
import org.strykeforce.thirdcoast.swerve.SwerveDriveConfig
23-
import org.strykeforce.thirdcoast.swerve.Wheel
24-
import org.strykeforce.thirdcoast.telemetry.TelemetryController
25-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
26-
import org.strykeforce.thirdcoast.telemetry.grapher.ClientHandler
23+
import org.strykeforce.telemetry.TelemetryController
24+
import org.strykeforce.telemetry.TelemetryService
25+
import org.strykeforce.telemetry.grapher.ClientHandler
2726
import java.net.DatagramSocket
27+
import java.net.InetSocketAddress
2828
import java.util.function.Function
2929

3030
private const val CLIENT_PORT = 5801
@@ -34,10 +34,18 @@ val tctModule = module {
3434

3535
factory { ClientHandler(CLIENT_PORT, DatagramSocket()) }
3636

37-
single { TelemetryService(Function { inventory -> TelemetryController(inventory, get(), SERVER_PORT) }) }
37+
single {
38+
TelemetryService(Function { inventory ->
39+
TelemetryController(
40+
inventory,
41+
get(),
42+
InetSocketAddress(SERVER_PORT)
43+
)
44+
})
45+
}
3846

3947
single { TalonService(get()) { id -> TalonSRX(id) } }
40-
48+
4149
single { TalonFxService(get()) { id -> TalonFX(id) } }
4250

4351
single { ServoService { id -> Servo(id) } }
@@ -60,16 +68,27 @@ val tctModule = module {
6068

6169
val swerveModule = module {
6270

63-
single {
64-
SwerveDriveConfig().apply {
65-
wheels = getWheels()
66-
}
67-
}
71+
single { SwerveDrive(*getSwerveModules()) }
72+
73+
}
6874

69-
single { SwerveDrive(get()) }
75+
private fun getSwerveModules() = Array<SwerveModule>(4) { i -> getSwerveModule(i) }
7076

77+
private val moduleBuilder = TalonSwerveModule.Builder().driveGearRatio(1.0).wheelDiameterInches(1.0)
78+
.driveMaximumMetersPerSecond(1.0)
79+
80+
private fun getSwerveModule(i: Int) : TalonSwerveModule {
81+
val location = when (i) {
82+
0 -> Translation2d(1.0, 1.0)
83+
1 -> Translation2d(1.0, -1.0)
84+
2 -> Translation2d(-1.0, 1.0)
85+
else -> Translation2d(-1.0, -1.0)
86+
}
87+
return moduleBuilder.azimuthTalon(TalonSRX(i)).driveTalon(TalonFX(i + 10))
88+
.wheelLocationMeters(location).build()
7189
}
7290

91+
/*
7392
private fun getWheels(): Array<Wheel> {
7493
val azimuthConfig = TalonSRXConfiguration().apply {
7594
primaryPID.selectedFeedbackSensor = FeedbackDevice.CTRE_MagEncoder_Relative
@@ -108,3 +127,4 @@ private fun getWheels(): Array<Wheel> {
108127
)
109128
}
110129
}
130+
*/

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

Lines changed: 7 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
package org.strykeforce.thirdcoast
22

3-
import edu.wpi.first.wpilibj.PowerDistribution
4-
import org.strykeforce.thirdcoast.telemetry.item.PowerDistributionPanelItem
53
import edu.wpi.first.wpilibj.TimedRobot
64
import mu.KotlinLogging
75
import net.consensys.cava.toml.Toml
@@ -11,8 +9,8 @@ import org.koin.log.Logger.SLF4JLogger
119
import org.koin.standalone.KoinComponent
1210
import org.koin.standalone.StandAloneContext.startKoin
1311
import org.koin.standalone.inject
12+
import org.strykeforce.telemetry.TelemetryService
1413
import org.strykeforce.thirdcoast.command.Command
15-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
1614
import kotlin.concurrent.thread
1715
import kotlin.system.exitProcess
1816

@@ -22,8 +20,7 @@ class Robot : TimedRobot(), KoinComponent {
2220

2321
override fun robotInit() {
2422
startKoin(listOf(tctModule, swerveModule), logger = SLF4JLogger())
25-
val telemetryService:TelemetryService by inject()
26-
// telemetryService.register(PowerDistributionPanelItem(PowerDistribution()))
23+
val telemetryService: TelemetryService by inject()
2724
thread(name = "tct", start = true) {
2825
val toml = parseResource("/commands.toml")
2926
val root = Command.createFromToml(toml)
@@ -54,9 +51,8 @@ fun parseResource(path: String): TomlTable {
5451
exitProcess(-1)
5552
}
5653

57-
fun loadResource(resource: String): String =
58-
try {
59-
object {}.javaClass.getResource(resource).readText(Charsets.UTF_8)
60-
} catch (all: Exception) {
61-
throw RuntimeException("Failed to load resource=$resource!", all)
62-
}
54+
fun loadResource(resource: String): String = try {
55+
object {}.javaClass.getResource(resource).readText(Charsets.UTF_8)
56+
} catch (all: Exception) {
57+
throw RuntimeException("Failed to load resource=$resource!", all)
58+
}

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
package org.strykeforce.thirdcoast.device
22

33
import com.ctre.phoenix.CANifier
4-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
5-
import org.strykeforce.thirdcoast.telemetry.item.CanifierItem
4+
import org.strykeforce.telemetry.TelemetryService
5+
import org.strykeforce.telemetry.measurable.CanifierMeasurable
66

77
class CanifierService(private val telemetryService: TelemetryService, factory: (id: Int) -> CANifier) :
88
AbstractDeviceService<CANifier>(factory) {
@@ -11,7 +11,7 @@ class CanifierService(private val telemetryService: TelemetryService, factory: (
1111
override fun activate(ids: Collection<Int>): Set<Int> {
1212
val new = super.activate(ids)
1313
telemetryService.stop()
14-
active.forEach { telemetryService.register(CanifierItem(it)) }
14+
active.forEach { telemetryService.register(CanifierMeasurable(it)) }
1515
telemetryService.start()
1616
return new
1717
}

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

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,18 @@
11
package org.strykeforce.thirdcoast.device
22

33
import com.ctre.phoenix.sensors.PigeonIMU
4-
import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame
5-
import org.strykeforce.thirdcoast.telemetry.item.PigeonIMUItem
64
import mu.KotlinLogging
7-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
5+
import org.strykeforce.telemetry.TelemetryService
6+
import org.strykeforce.telemetry.measurable.PigeonIMUMeasurable
87

98
private val logger = KotlinLogging.logger {}
109

1110
private const val DEFAULT_TEMP_COMP = false
1211

1312

14-
class PigeonService(private val telemetryService: TelemetryService, factory: (id: Int) -> PigeonIMU) :
15-
AbstractDeviceService<PigeonIMU>(factory) {
13+
class PigeonService(
14+
private val telemetryService: TelemetryService, factory: (id: Int) -> PigeonIMU
15+
) : AbstractDeviceService<PigeonIMU>(factory) {
1616

1717
val timeout = 10
1818
var tempCompensation = DEFAULT_TEMP_COMP
@@ -21,7 +21,7 @@ class PigeonService(private val telemetryService: TelemetryService, factory: (id
2121
override fun activate(ids: Collection<Int>): Set<Int> {
2222
val new = super.activate(ids)
2323
telemetryService.stop()
24-
active.forEach {telemetryService.register(PigeonIMUItem(it)) }
24+
active.forEach { telemetryService.register(PigeonIMUMeasurable(it)) }
2525
active.forEach {
2626
it.setTemperatureCompensationDisable(tempCompensation)
2727
}

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

Lines changed: 12 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,11 @@ 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.StatusFrame
6-
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced
75
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
86
import com.ctre.phoenix.motorcontrol.can.TalonFX
97
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration
108
import mu.KotlinLogging
11-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
12-
import java.lang.IllegalStateException
13-
import kotlin.math.log
9+
import org.strykeforce.telemetry.TelemetryService
1410

1511
private val logger = KotlinLogging.logger {}
1612

@@ -23,8 +19,9 @@ private const val SENSOR_PHASE_INVERTED_DEFAULT = false
2319
private const val OUTPUT_INVERTED_DEFAULT = false
2420

2521

26-
class TalonFxService(private val telemetryService: TelemetryService, factory: (id:Int) -> TalonFX ):
27-
AbstractDeviceService<TalonFX>(factory) {
22+
class TalonFxService(
23+
private val telemetryService: TelemetryService, factory: (id: Int) -> TalonFX
24+
) : AbstractDeviceService<TalonFX>(factory) {
2825

2926
val timeout = 10
3027
var dirty = true
@@ -36,14 +33,15 @@ class TalonFxService(private val telemetryService: TelemetryService, factory: (i
3633

3734
var activeConfiguration = TalonFXConfiguration()
3835
get() {
39-
if(!dirty) return field
40-
active.firstOrNull()?.getAllConfigs(field,timeout)?: logger.debug("no active talon fx's, returning default config")
36+
if (!dirty) return field
37+
active.firstOrNull()?.getAllConfigs(field, timeout)
38+
?: logger.debug("no active talon fx's, returning default config")
4139
dirty = false
4240
return field
4341
}
4442

4543
val activeSlot: SlotConfiguration
46-
get() = when(activeSlotIndex){
44+
get() = when (activeSlotIndex) {
4745
0 -> activeConfiguration.slot0
4846
1 -> activeConfiguration.slot1
4947
2 -> activeConfiguration.slot2
@@ -52,19 +50,19 @@ class TalonFxService(private val telemetryService: TelemetryService, factory: (i
5250
}
5351

5452
val outputInverted: Boolean
55-
get() = active.firstOrNull()?.inverted?: OUTPUT_INVERTED_DEFAULT
53+
get() = active.firstOrNull()?.inverted ?: OUTPUT_INVERTED_DEFAULT
5654

5755
override fun activate(ids: Collection<Int>): Set<Int> {
5856
dirty = true
5957

6058
val new = super.activate(ids)
6159
telemetryService.stop()
62-
active.filter { new.contains(it.deviceID) }.forEach(){
60+
active.filter { new.contains(it.deviceID) }.forEach {
6361
it.setNeutralMode(neutralMode)
64-
it.selectProfileSlot(activeSlotIndex,0)
62+
it.selectProfileSlot(activeSlotIndex, 0)
6563
it.enableVoltageCompensation(voltageCompensation)
6664
it.setSensorPhase(sensorPhase)
67-
it.setInverted(OUTPUT_INVERTED_DEFAULT)
65+
it.inverted = OUTPUT_INVERTED_DEFAULT
6866
telemetryService.register(it)
6967
}
7068
telemetryService.start()

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

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
77
import com.ctre.phoenix.motorcontrol.can.TalonSRX
88
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration
99
import mu.KotlinLogging
10-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
10+
import org.strykeforce.telemetry.TelemetryService
1111

1212
private val logger = KotlinLogging.logger {}
1313

@@ -55,12 +55,18 @@ class TalonService(private val telemetryService: TelemetryService, factory: (id:
5555
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
5656
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
5757
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)
58+
var supplyCurrentLimit = SupplyCurrentLimitConfiguration(
59+
SUPPLY_CURRENT_LIMIT_ENABLE_DEFAULT,
60+
SUPPLY_CURRENT_LIMIT_DEFAULT,
61+
SUPPLY_CURRENT_LIMIT_TRIG_CURRENT_DEFAULT,
62+
SUPPLY_CURRENT_LIMIT_TRIG_TIME_DEFAULT
63+
)
5964

6065
var activeConfiguration = TalonSRXConfiguration()
6166
get() {
6267
if (!dirty) return field
63-
active.firstOrNull()?.getAllConfigs(field) ?: logger.debug("no active talons, returning default config")
68+
active.firstOrNull()?.getAllConfigs(field)
69+
?: logger.debug("no active talons, returning default config")
6470
dirty = false
6571
return field
6672
}

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

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,18 @@
11
package org.strykeforce.thirdcoast.swerve
22

3+
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode
34
import edu.wpi.first.wpilibj.Timer
45
import mu.KotlinLogging
56
import net.consensys.cava.toml.TomlTable
67
import org.koin.standalone.inject
8+
import org.strykeforce.swerve.SwerveDrive
9+
import org.strykeforce.swerve.TalonSwerveModule
710
import org.strykeforce.thirdcoast.command.AbstractCommand
811
import org.strykeforce.thirdcoast.command.Command
912
import org.strykeforce.thirdcoast.command.prompt
1013
import org.strykeforce.thirdcoast.readInt
1114
import org.strykeforce.thirdcoast.warn
15+
import kotlin.math.abs
1216

1317
private val logger = KotlinLogging.logger {}
1418

@@ -46,18 +50,20 @@ class AdjustAzimuthCommand(
4650
toml: TomlTable
4751
) : AbstractCommand(parent, key, toml) {
4852

49-
val swerve: SwerveDrive by inject()
53+
private val swerve: SwerveDrive by inject()
5054

5155
override val menu: String
52-
get() = formatMenu(swerve.wheels[active].azimuthTalon.getSelectedSensorPosition(0))
56+
get() = formatMenu(
57+
(swerve.swerveModules[active] as TalonSwerveModule).azimuthTalon.getSelectedSensorPosition(0)
58+
)
5359

5460
override fun execute(): Command {
55-
val wheel = swerve.wheels[active]
56-
var position = wheel.azimuthTalon.getSelectedSensorPosition(0).toInt()
61+
val swerveModule = swerve.swerveModules[active] as TalonSwerveModule
62+
var position = swerveModule.azimuthTalon.getSelectedSensorPosition(0).toInt()
5763
while (true) {
5864
try {
5965
position = reader.readInt(prompt(), position)
60-
wheel.jogAround(position)
66+
swerveModule.jogAround(position.toDouble())
6167
logger.info { "positioned wheel $active to $position" }
6268
return super.execute()
6369
} catch (e: IllegalArgumentException) {
@@ -72,13 +78,13 @@ class AdjustAzimuthCommand(
7278
}
7379
}
7480

75-
private fun Wheel.jogAround(position: Int) {
81+
private fun TalonSwerveModule.jogAround(position: Double) {
7682
val positions = listOf(position - JOG, position + JOG, position)
7783
positions.forEach {
78-
this.setAzimuthPosition(it)
84+
this.azimuthTalon.set(TalonSRXControlMode.MotionMagic, it)
7985
while (!this.onTarget(it)) Timer.delay(DELAY)
8086
}
8187
}
8288

83-
internal fun Wheel.onTarget(target: Int, goodEnough: Int = GOOD_ENOUGH) =
84-
Math.abs(target - this.azimuthTalon.getSelectedSensorPosition(0)) < goodEnough
89+
internal fun TalonSwerveModule.onTarget(target: Double, goodEnough: Int = GOOD_ENOUGH) =
90+
abs(target - this.azimuthTalon.getSelectedSensorPosition(0)) < goodEnough

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

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,21 @@
11
package org.strykeforce.thirdcoast.swerve
22

3+
import mu.KotlinLogging
34
import net.consensys.cava.toml.TomlTable
45
import org.koin.standalone.inject
6+
import org.strykeforce.swerve.SwerveDrive
7+
import org.strykeforce.swerve.TalonSwerveModule
58
import org.strykeforce.thirdcoast.command.AbstractCommand
69
import org.strykeforce.thirdcoast.command.Command
710
import org.strykeforce.thirdcoast.command.prompt
811
import org.strykeforce.thirdcoast.info
912
import org.strykeforce.thirdcoast.readBoolean
1013
import org.strykeforce.thirdcoast.warn
1114

15+
private val logger = KotlinLogging.logger {}
16+
1217
class SaveZeroCommand(
13-
parent: Command?,
14-
key: String,
15-
toml: TomlTable
18+
parent: Command?, key: String, toml: TomlTable
1619
) : AbstractCommand(parent, key, toml) {
1720

1821
val swerve: SwerveDrive by inject()
@@ -21,8 +24,13 @@ class SaveZeroCommand(
2124
while (true) {
2225
try {
2326
if (reader.readBoolean(prompt(), false)) {
24-
swerve.saveAzimuthPositions()
25-
swerve.zeroAzimuthEncoders()
27+
swerve.swerveModules.forEach {
28+
val module = it as TalonSwerveModule
29+
30+
logger.debug { "azimuth ${module.azimuthTalon.deviceID}: store zero, before=${module.azimuthTalon.selectedSensorPosition}" }
31+
module.storeAzimuthZeroReference()
32+
logger.debug { "azimuth ${module.azimuthTalon.deviceID}: store zero, after=${module.azimuthTalon.selectedSensorPosition}" }
33+
}
2634
terminal.info("azimuth zero positions were saved")
2735
}
2836
return super.execute()

0 commit comments

Comments
 (0)