Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 27 additions & 0 deletions .roboRIOTeamNumberSetter/roborioteamnumbersetter-window.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"MainWindow": {
"GLOBAL": {
"font": "Proggy Dotted",
"fps": "120",
"height": "0",
"maximized": "0",
"style": "0",
"userScale": "2",
"width": "0",
"xpos": "-32000",
"ypos": "-32000"
}
},
"Window": {
"Debug##Default": {
"Collapsed": "0",
"Pos": "60,60",
"Size": "400,400"
},
"Entries": {
"Collapsed": "0",
"Pos": "0,0",
"Size": "46,32"
}
}
}
3 changes: 3 additions & 0 deletions .roboRIOTeamNumberSetter/roborioteamnumbersetter.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"TeamNumber": 2767
}
4 changes: 2 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@ import edu.wpi.first.gradlerio.deploy.roborio.RoboRIO
plugins {
id "java"
id "org.jetbrains.kotlin.jvm" version "1.9.0" //1.7.21
id "edu.wpi.first.GradleRIO" version "2024.3.1"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
}

version = "24.0.1"
version = "25.0.0"

sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
Expand Down
45 changes: 41 additions & 4 deletions src/main/kotlin/org/strykeforce/thirdcoast/Koin.kt
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
package org.strykeforce.thirdcoast

import com.ctre.phoenix.CANifier
import com.ctre.phoenix.motorcontrol.can.TalonFX
import com.ctre.phoenix.motorcontrol.can.TalonSRX
import com.ctre.phoenix.sensors.PigeonIMU
import com.ctre.phoenix6.hardware.CANcoder
import com.ctre.phoenix6.hardware.TalonFX
import com.ctre.phoenix6.hardware.TalonFXS
import edu.wpi.first.math.geometry.Translation2d
import edu.wpi.first.wpilibj.DigitalOutput
import edu.wpi.first.wpilibj.PneumaticsModuleType
Expand All @@ -14,6 +15,7 @@ import org.jline.reader.LineReader
import org.jline.reader.LineReaderBuilder
import org.jline.terminal.Terminal
import org.jline.terminal.TerminalBuilder
import org.koin.core.qualifier.named
import org.koin.dsl.module
//import org.koin.dsl.module.module
import org.strykeforce.swerve.*
Expand Down Expand Up @@ -45,12 +47,14 @@ val tctModule = module {

single { TalonService(get()) { id -> TalonSRX(id) } }

single { LegacyTalonFxService(get()) { id -> TalonFX(id) } }

single { TalonFxService(get()) { id -> com.ctre.phoenix6.hardware.TalonFX(id)} }

single {TalonFxFDService(get()) {id -> com.ctre.phoenix6.hardware.TalonFX(id, "*")} }

single {TalonFxsService(get()) {id -> com.ctre.phoenix6.hardware.TalonFXS(id)} }

single {TalonFXsFDService(get()) {id -> TalonFXS(id, "*")} }

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

single { SolenoidService { id -> Solenoid(PneumaticsModuleType.CTREPCM, id) } }
Expand All @@ -75,8 +79,16 @@ val tctModule = module {

val swerveModule = module {

single { SwerveDrive(*getSwerveModules()) }
single (named("V6")){ SwerveDrive(*getSwerveModules()) }

}

val fxSwerveModule = module {
single (named("FX")) {SwerveDrive(*getFXSwerveModules())}
}

val fxCANivoreSwerveModule = module {
single (named("FX-CANifier")) {SwerveDrive(*getCANivoreSwerveModules())}
}

private fun getSwerveModules() = Array<SwerveModule>(4) { i -> getSwerveModule(i) }
Expand All @@ -95,6 +107,31 @@ private fun getSwerveModule(i: Int) : V6TalonSwerveModule {
.wheelLocationMeters(location).build()
}

private fun getFXSwerveModules() = Array<SwerveModule>(4) {i -> getFXSwerveModule(i)}
private fun getCANivoreSwerveModules() = Array<SwerveModule>(4) {i -> getCANivoreSwerveModule(i) }
private val fxModuleBuilder = FXSwerveModule.FXBuilder().driveGearRatio(1.0).wheelDiameterInches(1.0).driveMaximumMetersPerSecond(1.0)

private fun getFXSwerveModule(i:Int): FXSwerveModule {
val location = when(i) {
0 -> Translation2d(1.0, 1.0)
1 -> Translation2d(1.0, -1.0)
2 -> Translation2d(-1.0, 1.0)
else -> Translation2d(-1.0, -1.0)
}
return fxModuleBuilder.azimuthTalon(TalonFXS(i)).driveTalon(TalonFX(i+10)).wheelLocationMeters(location).build()
}

private fun getCANivoreSwerveModule(i: Int): FXSwerveModule {
val location = when(i) {
0 -> Translation2d(1.0, 1.0)
1 -> Translation2d(1.0, -1.0)
2 -> Translation2d(-1.0, 1.0)
else -> Translation2d(-1.0, -1.0)
}
return fxModuleBuilder.azimuthTalon(TalonFXS(i,"*")).driveTalon(TalonFX(i+10,"*")).wheelLocationMeters(location).build()
}


/*
private fun getWheels(): Array<Wheel> {
val azimuthConfig = TalonSRXConfiguration().apply {
Expand Down
2 changes: 1 addition & 1 deletion src/main/kotlin/org/strykeforce/thirdcoast/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ class Robot : TimedRobot(), KoinComponent {

override fun robotInit() {
startKoin{
modules(listOf(tctModule, swerveModule))
modules(listOf(tctModule, swerveModule, fxSwerveModule, fxCANivoreSwerveModule))
logger(SLF4JLogger())
}
val telemetryService: TelemetryService by inject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@ class CancoderParameter(
): AbstractParameter(command, toml) {
enum class Enum {
POSITION,
MAG_OFFSET
MAG_OFFSET,
DISCONTINUITY_POINT
}

companion object {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@ package org.strykeforce.thirdcoast.cancoder

import com.ctre.phoenix6.configs.CANcoderConfiguration
import com.ctre.phoenix6.hardware.CANcoder
import edu.wpi.first.units.Units
import edu.wpi.first.units.Units.Rotations
import edu.wpi.first.units.measure.Angle
import mu.KotlinLogging
import net.consensys.cava.toml.TomlTable
//import org.koin.standalone.inject
Expand Down Expand Up @@ -38,6 +41,10 @@ class CancoderParameterCommand(
MAG_OFFSET -> formatMenu(
if(bus == "rio") cancoderService.activeConfiguration.MagnetSensor.MagnetOffset
else cancoderFDService.activeConfiguration.MagnetSensor.MagnetOffset)
DISCONTINUITY_POINT -> formatMenu(
if(bus == "rio") cancoderService.activeConfiguration.MagnetSensor.AbsoluteSensorDiscontinuityPoint
else cancoderFDService.activeConfiguration.MagnetSensor.AbsoluteSensorDiscontinuityPoint
)
}
}

Expand All @@ -53,6 +60,12 @@ class CancoderParameterCommand(
activeConfig.MagnetSensor.MagnetOffset = value
cancoder.configurator.apply(activeConfig)
}
DISCONTINUITY_POINT -> configDoubleParam(activeConfig.MagnetSensor.absoluteSensorDiscontinuityPointMeasure.`in`(
Rotations)) {
caNcoder, value ->
activeConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = value
caNcoder.configurator.apply(activeConfig)
}
else -> TODO("${param.name} not implemented")
}
return super.execute()
Expand All @@ -73,6 +86,22 @@ class CancoderParameterCommand(
} else throw IllegalArgumentException()
}

private fun configAngleParameter(default: Angle, config: (CANcoder, Angle) -> Unit) {
val paramValue = param.readDouble(reader, default.`in`(Units.Rotations))
if(bus == "rio") {
cancoderService.active.forEach {
config(it, Rotations.of(paramValue))
logger.info { "set ${cancoderService.active.size} CANcoder's ${param.name}: $paramValue" }
}
} else if(bus == "canivore") {
cancoderFDService.active.forEach {
config(it, Rotations.of(paramValue))
logger.info { "set ${cancoderFDService.active.size} CANcoder's ${param.name}: $paramValue" }
}
} else throw IllegalArgumentException()
}


private fun configIntParameter(default: Int, config: (CANcoder, Int) -> Unit) {
val paramValue = param.readInt(reader, default)
if(bus == "rio") {
Expand Down

This file was deleted.

19 changes: 11 additions & 8 deletions src/main/kotlin/org/strykeforce/thirdcoast/command/Command.kt
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,7 @@ import org.strykeforce.thirdcoast.servo.RunServosCommand
import org.strykeforce.thirdcoast.servo.SelectServosCommand
import org.strykeforce.thirdcoast.solenoid.RunSolenoidsCommand
import org.strykeforce.thirdcoast.solenoid.SelectSolenoidsCommand
import org.strykeforce.thirdcoast.swerve.AdjustAzimuthCommand
import org.strykeforce.thirdcoast.swerve.SaveZeroCommand
import org.strykeforce.thirdcoast.swerve.SelectAzimuthCommand
import org.strykeforce.thirdcoast.swerve.SetAzimuthCommand
import org.strykeforce.thirdcoast.swerve.*
import org.strykeforce.thirdcoast.talon.*
import org.strykeforce.thirdcoast.talon.phoenix6.*

Expand Down Expand Up @@ -66,9 +63,6 @@ interface Command {
"talon.hard.source" -> SelectHardLimitSourceCommand(parent, key, toml)
"talon.hard.normal" -> SelectHardLimitNormalCommand(parent, key, toml)
"talon.velocity.period" -> SelectVelocityMeasurmentPeriodCommand(parent, key, toml)
"talon.commutation" -> SelectMotorCommutationCommand(parent, key, toml)
"talon.absoluteRange" -> SelectAbsoluteSensorRange(parent, key, toml)
"talon.initStrategy" -> SelectInitializationStrategy(parent, key, toml)
"servo.select" -> SelectServosCommand(parent, key, toml)
"servo.run" -> RunServosCommand(parent, key, toml)
"solenoid.select" -> SelectSolenoidsCommand(parent, key, toml)
Expand All @@ -86,6 +80,10 @@ interface Command {
"swerve.azimuth.save" -> SaveZeroCommand(parent, key, toml)
"swerve.azimuth.select" -> SelectAzimuthCommand(parent, key, toml)
"swerve.azimuth.adjust" -> AdjustAzimuthCommand(parent, key, toml)
"p6.swerve.azimuth" -> P6SetAzimuthCommand(parent, key, toml)
"p6.swerve.azimuth.save" -> P6SaveZeroCommand(parent, key, toml)
"p6.swerve.azimuth.select" -> P6SelectAzimuthCommand(parent, key, toml)
"p6.swerve.azimuth.adjust" -> P6AdjustAzimuthCommand(parent, key, toml)
"pigeon.select" -> SelectPigeonCommand(parent, key, toml)
"pigeon.param" -> PigeonParameterCommand(parent, key, toml)
"p6.run" -> P6RunCommand(parent, key, toml)
Expand All @@ -98,6 +96,7 @@ interface Command {
"p6.feedback" -> P6SelectFeedbackSensorCommand(parent, key, toml)
"p6.mmType" -> P6SelectMotionMagicTypeCommand(parent, key, toml)
"p6.diffType" -> P6SelectDifferentialTypeCommand(parent, key, toml)
"p6.diffSource" -> P6SelectDifferentialSensorSourceCommand(parent, key, toml)
"p6.followType" -> P6SelectFollowerTypeCommand(parent, key, toml)
"p6.neutralOut" -> P6SelectNeutralOutputCommand(parent, key, toml)
"p6.units" -> P6SelectUnitCommand(parent, key, toml)
Expand All @@ -111,10 +110,14 @@ interface Command {
"p6.revSource" -> P6SelectRevHardLimitSourceCommand(parent, key, toml)
"p6.factory" -> P6FactoryDefaultCommand(parent, key, toml)
"p6.graph" -> P6DefaultStatusFrameCommand(parent, key, toml)
"p6.extFeedback" -> P6SelectExternalFeedbackSourceCommand(parent, key, toml)
"p6.phase" -> P6SelectSensorPhaseCommand(parent, key, toml)
"p6.motorArrange" -> P6SelectMotorArrangementCommand(parent, key, toml)
"p6.wiring" -> P6SelectBrushedWiringCommand(parent, key, toml)
"p6.advHall" -> P6SelectAdvancedHallSupportCommand(parent, key, toml)
"cancoder.select" -> SelectCancoderCommand(parent, key, toml)
"cancoder.status" -> CancoderStatusCommand(parent, key, toml)
"cancoder.param" -> CancoderParameterCommand(parent, key, toml)
"cancoder.absRange" -> SelectAbsRangeValueCommand(parent, key, toml)
"cancoder.sensorDirection" -> SelectCancoderSensorDirectionCommand(parent, key, toml)
else -> DefaultCommand(parent, key, toml)
}
Expand Down

This file was deleted.

Loading