Skip to content
This repository has been archived by the owner on Dec 19, 2024. It is now read-only.

Commit

Permalink
Merge branch 'main' into Arm
Browse files Browse the repository at this point in the history
# Conflicts:
#	src/main/java/com/frcteam3636/frc2024/Robot.kt
  • Loading branch information
NikolaJenkins committed Nov 14, 2024
2 parents c0a312e + f35064c commit 88957e7
Show file tree
Hide file tree
Showing 6 changed files with 44 additions and 10 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ tasks.register('checkAkitInstall', JavaExec) {
}
compileJava.finalizedBy checkAkitInstall

project.compileJava.dependsOn(createVersionFile)
project.assemble.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = ""
Expand Down
9 changes: 5 additions & 4 deletions src/main/java/com/frcteam3636/frc2024/Robot.kt
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
package com.frcteam3636.frc2024

import BuildConstants
import com.ctre.phoenix6.SignalLogger
import com.ctre.phoenix6.StatusSignal
import com.frcteam3636.frc2024.subsystems.arm.Arm
import com.frcteam3636.frc2024.subsystems.drivetrain.Drivetrain
Expand Down Expand Up @@ -73,9 +71,11 @@ object Robot : LoggedRobot() {

/** Start logging or pull replay logs from a file */
private fun configureAdvantageKit() {
Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA)
Logger.recordMetadata("Git SHA", BuildConstants.GIT_SHA)
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE)
Logger.recordMetadata("Model", model.name)
Logger.recordMetadata("Git Dirty", BuildConstants.DIRTY.toString())
Logger.recordMetadata("Git Branch", BuildConstants.GIT_BRANCH)

if (isReal()) {
Logger.addDataReceiver(WPILOGWriter()) // Log to a USB stick
Expand Down Expand Up @@ -211,7 +211,7 @@ object Robot : LoggedRobot() {

/** A model of robot, depending on where we're deployed to. */
enum class Model {
SIMULATION, COMPETITION,
SIMULATION, COMPETITION, PROTOTYPE
}

/** The model of this robot. */
Expand All @@ -220,6 +220,7 @@ object Robot : LoggedRobot() {
} else {
when (val key = Preferences.getString("Model", "competition")) {
"competition" -> Model.COMPETITION
"prototype" -> Model.PROTOTYPE
else -> throw Exception("invalid model found in preferences: $key")
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ object Drivetrain : Subsystem, Sendable {
private val io = when (Robot.model) {
Robot.Model.SIMULATION -> DrivetrainIOSim()
Robot.Model.COMPETITION -> DrivetrainIOReal.fromKrakenSwerve()
Robot.Model.PROTOTYPE -> DrivetrainIOReal.fromNeoSwerve()
}
val inputs = DrivetrainIO.Inputs()

Expand Down Expand Up @@ -84,10 +85,7 @@ object Drivetrain : Subsystem, Sendable {

init {
Pathfinding.setPathfinder(
when (Robot.model) {
Robot.Model.SIMULATION -> LocalADStarAK()
Robot.Model.COMPETITION -> RemoteADStarAK()
}
LocalADStarAK()
)

AutoBuilder.configureHolonomic(
Expand Down Expand Up @@ -358,6 +356,30 @@ object Drivetrain : Subsystem, Sendable {
),
)

internal val MODULE_CAN_IDS_PRACTICE =
PerCorner(
frontLeft =
Pair(
REVMotorControllerId.FrontLeftDrivingMotor,
REVMotorControllerId.FrontLeftTurningMotor
),
frontRight =
Pair(
REVMotorControllerId.FrontRightDrivingMotor,
REVMotorControllerId.FrontRightTurningMotor
),
backRight =
Pair(
REVMotorControllerId.BackRightDrivingMotor,
REVMotorControllerId.BackRightTurningMotor
),
backLeft =
Pair(
REVMotorControllerId.BackLeftDrivingMotor,
REVMotorControllerId.BackLeftTurningMotor
),
)

/** A position with the modules radiating outwards from the center of the robot, preventing movement. */
val BRAKE_POSITION = MODULE_POSITIONS.map { position -> SwerveModuleState(0.0, position.translation.angle) }
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,16 @@ class DrivetrainIOReal(override val modules: PerCorner<out SwerveModule>) : Driv
position.rotation
)
})

fun fromNeoSwerve() =
DrivetrainIOReal(Drivetrain.Constants.MODULE_POSITIONS.zip(Drivetrain.Constants.MODULE_CAN_IDS_PRACTICE).map { (position, ids) ->
val (driveId, turnId) = ids
MAXSwerveModule(
DrivingSparkMAX(driveId),
turnId,
position.rotation
)
})
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ object Intake: Subsystem {
private var io: IntakeIO = when (Robot.model) {
Robot.Model.SIMULATION -> IntakeIO.IntakeIOSim()
Robot.Model.COMPETITION -> IntakeIO.IntakeIOReal()
Robot.Model.PROTOTYPE -> IntakeIO.IntakeIOSim()
}

var inputs = IntakeIO.IntakeInputs()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ object Wrist: Subsystem {
var inputs = IntakeIO.IntakeInputs()

override fun periodic() {
Logger.processInputs("Intake", inputs)
Logger.processInputs("Wrist", inputs)
//the wrist should always be parallel to the ground
io.pivotToAndStop(Arm.inputs.position * -1.0) //use position variable from arm
}
Expand Down

0 comments on commit 88957e7

Please sign in to comment.