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

Commit

Permalink
feat: switch I/O implementations per robot model
Browse files Browse the repository at this point in the history
  • Loading branch information
max-niederman committed Feb 1, 2024
1 parent 6dae26b commit fa6489b
Show file tree
Hide file tree
Showing 7 changed files with 78 additions and 101 deletions.
68 changes: 46 additions & 22 deletions src/main/java/com/frcteam3636/frc2024/Robot.kt
Original file line number Diff line number Diff line change
@@ -1,18 +1,25 @@
package com.frcteam3636.frc2024

import com.frcteam3636.frc2024.subsystems.drivetrain.Drivetrain
import com.frcteam3636.frc2024.subsystems.intake.Intake
import com.frcteam3636.frc2024.subsystems.shooter.Shooter
import edu.wpi.first.hal.FRCNetComm.tInstances
import edu.wpi.first.hal.FRCNetComm.tResourceType
import edu.wpi.first.hal.HAL
import edu.wpi.first.wpilibj.Joystick
import edu.wpi.first.wpilibj.PowerDistribution
import edu.wpi.first.wpilibj.Preferences
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.util.WPILibVersion
import edu.wpi.first.wpilibj2.command.Command
import edu.wpi.first.wpilibj2.command.CommandScheduler
import edu.wpi.first.wpilibj2.command.button.CommandXboxController
import org.littletonrobotics.junction.LogFileUtil
import org.littletonrobotics.junction.LoggedRobot
import org.littletonrobotics.junction.Logger
import org.littletonrobotics.junction.networktables.NT4Publisher
import org.littletonrobotics.junction.wpilog.WPILOGReader
import org.littletonrobotics.junction.wpilog.WPILOGWriter
import kotlin.Exception

/**
* The VM is configured to automatically run this object (which basically functions as a singleton
Expand All @@ -26,8 +33,9 @@ import org.littletonrobotics.junction.wpilog.WPILOGWriter
* renaming the object or package, it will get changed everywhere.)
*/
object Robot : LoggedRobot() {

private var autonomousCommand: Command? = null
private val controller = CommandXboxController(0)
private val joystickLeft = Joystick(0)
private val joystickRight = Joystick(1)

override fun robotInit() {
// Report the use of the Kotlin Language for "FRC Usage Report" statistics
Expand Down Expand Up @@ -68,41 +76,57 @@ object Robot : LoggedRobot() {
Logger.start() // Start logging! No more data receivers, replay sources, or metadata values
// may be added.

// Access the RobotContainer object so that it is initialized. This will perform all our
// button bindings, and put our autonomous chooser on the dashboard.
RobotContainer
// initialize and register our subsystems
Shooter.register()
Drivetrain.register()
Intake.register()

// Configure our button and joystick bindings
configureBindings()
}

private fun configureBindings() {
controller.x().whileTrue(Shooter.shootCommand())
controller.b().whileTrue(Intake.intakeCommand())
Drivetrain.defaultCommand =
Drivetrain.driveWithJoysticks(
translationJoystick = joystickLeft,
rotationJoystick = joystickRight
)
}

override fun robotPeriodic() {
CommandScheduler.getInstance().run()
}

override fun disabledInit() {}

override fun disabledPeriodic() {}

override fun autonomousInit() {
autonomousCommand = RobotContainer.getAutonomousCommand()
autonomousCommand?.schedule()
// TODO: start autonomous command
}

override fun autonomousPeriodic() {}

override fun teleopInit() {
autonomousCommand?.cancel()
// TODO: cancel autonomous command
}

/** This method is called periodically during operator control. */
override fun teleopPeriodic() {}

override fun testInit() {
// Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll()
}

override fun testPeriodic() {}

override fun simulationInit() {}
// A model of robot, depending on where we're deployed to.
enum class Model {
SIMULATION,
PRACTICE,
COMPETITION,
}

override fun simulationPeriodic() {}
// The model of this robot.
val model: Model = if (RobotBase.isSimulation()) {
Model.SIMULATION
} else {
when (val key = Preferences.getString("Model", "competition")) {
"competition" -> Model.COMPETITION
"practice" -> Model.PRACTICE
else -> throw Exception("invalid model found in preferences: $key")
}
}
}
47 changes: 0 additions & 47 deletions src/main/java/com/frcteam3636/frc2024/RobotContainer.kt

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
package com.frcteam3636.frc2024.subsystems.climber

import com.frcteam3636.frc2024.Robot
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj2.command.Subsystem
import org.littletonrobotics.junction.Logger

class Climber : Subsystem {
private var io: ClimberIO =
if (RobotBase.isReal()) {
ClimberIOReal()
} else {
TODO()
}
private var io: ClimberIO = when (Robot.model) {
Robot.Model.PRACTICE -> ClimberIOReal()
Robot.Model.COMPETITION -> ClimberIOReal()
Robot.Model.SIMULATION -> TODO()
}
var inputs = ClimberIO.ClimberInputs()

override fun periodic() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ package com.frcteam3636.frc2024.subsystems.drivetrain

import com.frcteam3636.frc2024.CTREMotorControllerId
import com.frcteam3636.frc2024.REVMotorControllerId
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.utils.swerve.PerCorner
import com.frcteam3636.frc2024.utils.swerve.cornerStatesToChassisSpeeds
import com.frcteam3636.frc2024.utils.swerve.toCornerSwerveModuleStates
Expand All @@ -26,12 +27,11 @@ import org.littletonrobotics.junction.inputs.LoggableInputs

// A singleton object representing the drivetrain.
object Drivetrain : Subsystem {
private val io =
if (RobotBase.isReal()) {
DrivetrainIOReal()
} else {
DrivetrainIOSim()
}
private val io = when (Robot.model) {
Robot.Model.SIMULATION -> DrivetrainIOSim()
Robot.Model.COMPETITION -> DrivetrainIOComp()
Robot.Model.PRACTICE -> TODO()
}
private val inputs = DrivetrainIO.Inputs()

// Create swerve drivetrain kinematics using the translation parts of the module positions.
Expand Down Expand Up @@ -168,7 +168,7 @@ abstract class DrivetrainIO {
}
}

class DrivetrainIOReal : DrivetrainIO() {
class DrivetrainIOComp : DrivetrainIO() {
override val gyro = GyroNavX()
override val modules =
MODULE_CAN_IDS.zip(MODULE_POSITIONS).map { (can, pose) ->
Expand Down
Original file line number Diff line number Diff line change
@@ -1,16 +1,15 @@
package com.frcteam3636.frc2024.subsystems.intake

import edu.wpi.first.wpilibj.RobotBase
import com.frcteam3636.frc2024.Robot
import edu.wpi.first.wpilibj2.command.*
import org.littletonrobotics.junction.Logger

object Intake : Subsystem {
private var io: IntakeIO =
if (RobotBase.isReal()) {
IntakeIOReal()
} else {
IntakeIOSim()
}
private var io: IntakeIO = when (Robot.model) {
Robot.Model.SIMULATION -> IntakeIOSim()
Robot.Model.COMPETITION -> IntakeIOReal()
Robot.Model.PRACTICE -> IntakeIOReal()
}

var inputs = IntakeIO.IntakeInputs()

Expand All @@ -30,9 +29,9 @@ object Intake : Subsystem {

fun indexCommand(): Command {
return SequentialCommandGroup(
runOnce({ io.setUnderBumperRoller(1.0) }),
runOnce { io.setUnderBumperRoller(1.0) },
WaitCommand(1.0),
runOnce({ io.setUnderBumperRoller(0.0) })
runOnce { io.setUnderBumperRoller(0.0) }
)
}
}
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
package com.frcteam3636.frc2024.subsystems.shooter

import com.ctre.phoenix6.controls.MotionMagicTorqueCurrentFOC
import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.utils.math.PIDController
import com.frcteam3636.frc2024.utils.math.PIDGains
import edu.wpi.first.math.filter.SlewRateLimiter
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard
import edu.wpi.first.wpilibj2.command.Command
Expand All @@ -15,14 +15,10 @@ import org.littletonrobotics.junction.Logger

object Shooter : Subsystem {

const val ACCELERATION_PROFILE = 0.0
const val VELOCITY_PROFILE = 0.0
const val JERK_PROFILE = 0.0

private val io: ShooterIO = if (RobotBase.isReal()) {
ShooterIOReal()
} else {
TODO()
private val io: ShooterIO = when (Robot.model) {
Robot.Model.SIMULATION -> TODO()
Robot.Model.COMPETITION -> ShooterIOComp()
Robot.Model.PRACTICE -> TODO()
}

private val pidController = PIDController(PIDGains(0.1, 0.0, 0.0))
Expand Down Expand Up @@ -67,3 +63,8 @@ object Shooter : Subsystem {
fun intakeCommand(): Command =
startEnd({ io.intake(1.0) }, { io.intake(0.0) })
}

internal const val ACCELERATION_PROFILE = 0.0
internal const val VELOCITY_PROFILE = 0.0
internal const val JERK_PROFILE = 0.0

Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ interface ShooterIO {
fun setPivotControlRequest(control: ControlRequest)
}

class ShooterIOReal : ShooterIO {
class ShooterIOComp : ShooterIO {

internal companion object Constants {
const val FLYWHEEL_GEAR_RATIO = 1.0
Expand Down

0 comments on commit fa6489b

Please sign in to comment.