diff --git a/.gitignore b/.gitignore index 3325f5c0..2f879e83 100644 --- a/.gitignore +++ b/.gitignore @@ -138,6 +138,7 @@ $RECYCLE.BIN/ ### Gradle ### .gradle /build/ +BuildConstants.kt # Ignore Gradle GUI config gradle-app.setting @@ -168,5 +169,8 @@ out/ # Fleet .fleet + # Simulation GUI and other tools window save file *-window.json + +src/main/kotlin/com/team4099/robot2023/BuildConstants.kt diff --git a/build.gradle b/build.gradle index a21179a3..ba2238c0 100644 --- a/build.gradle +++ b/build.gradle @@ -83,7 +83,7 @@ dependencies { simulationRelease wpi.sim.enableRelease() implementation 'org.jetbrains.kotlin:kotlin-test-junit5' - implementation 'com.github.team4099:FalconUtils:1.1.26' + implementation 'com.github.team4099:FalconUtils:1.1.28' implementation 'org.apache.commons:commons-collections4:4.0' implementation 'com.google.code.gson:gson:2.10.1' implementation "io.javalin:javalin:5.3.2" diff --git a/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt b/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt index 0fd15fdc..383fd40c 100644 --- a/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt +++ b/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt @@ -12,6 +12,7 @@ import org.team4099.lib.units.perSecond import com.ctre.phoenix6.controls.PositionVoltage as PositionVoltagePhoenix6 class PositionVoltage( + private var position: Angle, // Assuming an AngularPosition type exists similar to AngularVelocity private var enableFOC: Boolean = true, private var feedforward: ElectricalPotential = 0.0.volts, @@ -20,6 +21,7 @@ class PositionVoltage( private var limitForwardMotion: Boolean = false, private var limitReverseMotion: Boolean = false, private var velocity: AngularVelocity = 0.0.degrees.perSecond, + ) { val positionVoltagePhoenix6 = PositionVoltagePhoenix6(position.inRotations, velocity.inRotationsPerSecond, enableFOC, feedforward.inVolts, slot, overrideBrakeDurNeutral, limitForwardMotion, limitReverseMotion) diff --git a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt b/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt deleted file mode 100644 index 24e5d450..00000000 --- a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt +++ /dev/null @@ -1,15 +0,0 @@ -package com.team4099.robot2023 - -/** - * Automatically generated file containing build version information. - */ -const val MAVEN_GROUP = "" -const val MAVEN_NAME = "Crescendo-2024" -const val VERSION = "unspecified" -const val GIT_REVISION = 34 -const val GIT_SHA = "d5fd1849cf1454f10fbe3db431150aff1c19e8cc" -const val GIT_DATE = "2024-01-19T23:40:38Z" -const val GIT_BRANCH = "intake" -const val BUILD_DATE = "2024-01-20T00:01:13Z" -const val BUILD_UNIX_TIME = 1705726873776L -const val DIRTY = 1 diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIOSim.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIOSim.kt deleted file mode 100644 index 801b2e84..00000000 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIOSim.kt +++ /dev/null @@ -1,53 +0,0 @@ -package com.team4099.robot2023.subsystems.intake - -import com.team4099.lib.math.clamp -import com.team4099.robot2023.config.constants.Constants -import com.team4099.robot2023.config.constants.IntakeConstants -import edu.wpi.first.math.system.plant.DCMotor -import edu.wpi.first.wpilibj.simulation.FlywheelSim -import org.team4099.lib.units.base.amps -import org.team4099.lib.units.base.celsius -import org.team4099.lib.units.base.inSeconds -import org.team4099.lib.units.derived.ElectricalPotential -import org.team4099.lib.units.derived.inVolts -import org.team4099.lib.units.derived.rotations -import org.team4099.lib.units.derived.volts -import org.team4099.lib.units.perMinute - -object IntakeIOSim : IntakeIO { - private val rollerSim: FlywheelSim = FlywheelSim( - DCMotor.getNEO(1), - IntakeConstants.ROLLER_GEAR_RATIO, - IntakeConstants.ROLLER_INERTIA - ) - - private var appliedVoltage = 0.volts; - init{} - - override fun updateInputs(inputs: IntakeIO.IntakeIOInputs) { - - rollerSim.update(Constants.Universal.LOOP_PERIOD_TIME.inSeconds) - - inputs.rollerVelocity = rollerSim.getAngularVelocityRPM().rotations.perMinute - inputs.rollerAppliedVoltage = appliedVoltage - inputs.rollerSupplyCurrent = 0.amps - inputs.rollerStatorCurrent = rollerSim.currentDrawAmps.amps - inputs.rollerTemp = 0.0.celsius - - inputs.isSimulated = true - } - - override fun setRollerVoltage(voltage: ElectricalPotential) { - appliedVoltage = voltage - rollerSim.setInputVoltage( - clamp( - voltage, - -IntakeConstants.VOLTAGE_COMPENSATION, - IntakeConstants.VOLTAGE_COMPENSATION - ) - .inVolts - ) - } - - override fun setRollerBrakeMode(brake: Boolean) {} -} diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt index 9c77f65b..c5259f97 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt @@ -17,51 +17,6 @@ import org.team4099.lib.units.perSecond sealed interface Request { - sealed interface SuperstructureRequest : Request { - class Idle() : SuperstructureRequest - class Home() : SuperstructureRequest - - class GroundIntakeCube() : SuperstructureRequest - class GroundIntakeCone() : SuperstructureRequest - - class EjectGamePiece() : SuperstructureRequest - - class DoubleSubstationIntakePrep(val gamePiece: GamePiece) : SuperstructureRequest - class SingleSubstationIntakePrep(val gamePiece: GamePiece) : SuperstructureRequest - - class DoubleSubstationIntake() : SuperstructureRequest - class SingleSubstationIntake(val gamePiece: GamePiece) : SuperstructureRequest - - class PrepScore(val gamePiece: GamePiece, val nodeTier: NodeTier) : SuperstructureRequest - - class Score() : SuperstructureRequest - - class Tuning() : SuperstructureRequest - } - - // Implements RequestStructure to ensure standardized structure - sealed interface ManipulatorRequest : Request { - class TargetingPosition(val position: Length, val rollerVoltage: ElectricalPotential) : - ManipulatorRequest - class OpenLoop(val voltage: ElectricalPotential, val rollerVoltage: ElectricalPotential) : - ManipulatorRequest - class Home() : ManipulatorRequest - } - - sealed interface ElevatorRequest : Request { - class TargetingPosition( - val position: Length, - val finalVelocity: LinearVelocity = 0.0.inches.perSecond, - val canContinueBuffer: Length = 5.0.inches - ) : ElevatorRequest - class OpenLoop(val voltage: ElectricalPotential) : ElevatorRequest - class Home : ElevatorRequest - } - - sealed interface IntakeRequest : Request { - class OpenLoop(val rollerVoltage: ElectricalPotential) : IntakeRequest - } - sealed interface DrivetrainRequest : Request { class OpenLoop( val angularVelocity: AngularVelocity, @@ -76,4 +31,8 @@ sealed interface Request { class ZeroSensors : DrivetrainRequest class Idle : DrivetrainRequest } + + sealed interface IntakeRequest : Request { + class OpenLoop(val rollerVoltage: ElectricalPotential) : IntakeRequest + } } diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index eb271997..f86862cc 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,7 +1,7 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2024.0.0-beta-6", + "version": "2024.1.3", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2024", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2024.0.0-beta-6" + "version": "2024.1.3" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2024.0.0-beta-6", + "version": "2024.1.3", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false,