Skip to content

Commit

Permalink
wpilib deprecations
Browse files Browse the repository at this point in the history
  • Loading branch information
theKnightedBird committed Jan 16, 2025
1 parent c3528f9 commit 9cd9e99
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 36 deletions.
14 changes: 10 additions & 4 deletions src/main/kotlin/frc/team449/Main.kt
Original file line number Diff line number Diff line change
@@ -1,9 +1,15 @@
@file:JvmName("Main")

package frc.team449

import edu.wpi.first.wpilibj.RobotBase

fun main() {
object Main {
/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the argument type.
*/
@JvmStatic
fun main(args: Array<String>) {
RobotBase.startRobot { RobotLoop() }
}
}
}
13 changes: 8 additions & 5 deletions src/main/kotlin/frc/team449/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ package frc.team449

import edu.wpi.first.epilogue.Logged
import edu.wpi.first.wpilibj.PowerDistribution
import edu.wpi.first.wpilibj.smartdashboard.Field2d
import edu.wpi.first.wpilibj2.command.button.CommandXboxController
import frc.team449.subsystems.RobotConstants
import frc.team449.subsystems.drive.swerve.SwerveDrive
Expand All @@ -16,23 +17,25 @@ import frc.team449.subsystems.vision.PoseSubsystem.Companion.createPoseSubsystem
import frc.team449.system.AHRS

@Logged
class Robot : RobotBase() {
class Robot {

val driveController = CommandXboxController(0)

val mechController = CommandXboxController(1)

val ahrs = AHRS()

val field = Field2d()

// Instantiate/declare PDP and other stuff here
override val powerDistribution: PowerDistribution =
val powerDistribution: PowerDistribution =
PowerDistribution(RobotConstants.PDH_CAN, PowerDistribution.ModuleType.kRev)

override val drive: SwerveDrive = SwerveDrive.createSwerveKraken(field)
val drive: SwerveDrive = SwerveDrive.createSwerveKraken(field)

override val poseSubsystem: PoseSubsystem = createPoseSubsystem(ahrs, drive, field)
val poseSubsystem: PoseSubsystem = createPoseSubsystem(ahrs, drive, field)

override val driveCommand: SwerveOrthogonalCommand =
val driveCommand: SwerveOrthogonalCommand =
SwerveOrthogonalCommand(drive, poseSubsystem, driveController.hid)

val elevator: Elevator = createElevator()
Expand Down
20 changes: 0 additions & 20 deletions src/main/kotlin/frc/team449/RobotBase.kt

This file was deleted.

11 changes: 4 additions & 7 deletions src/main/kotlin/frc/team449/RobotLoop.kt
Original file line number Diff line number Diff line change
Expand Up @@ -27,20 +27,15 @@ class RobotLoop : TimedRobot() {
private val robot = Robot()

private val routineChooser: RoutineChooser = RoutineChooser(robot)

private val field = robot.field
private var autoCommand: Command? = null
private var routineMap = hashMapOf<String, Command>()
private val controllerBinder =
ControllerBindings(robot.driveController, robot.mechController, robot)

override fun robotInit() {
init {
// Yes this should be a print statement, it's useful to know that robotInit started.
println("Started robotInit.")

SignalLogger.setPath("/media/sda1/ctre-logs/")
SignalLogger.start()

HAL.report(
FRCNetComm.tResourceType.kResourceType_Language,
FRCNetComm.tInstances.kLanguage_Kotlin,
Expand All @@ -67,8 +62,10 @@ class RobotLoop : TimedRobot() {

controllerBinder.bindButtons()

SignalLogger.setPath("/media/sda1/ctre-logs/")
SignalLogger.start()
Epilogue.bind(this)
DriverStation.startDataLog(DataLogManager.getLog())
DataLogManager.start()
}

override fun driverStationConnected() {}
Expand Down

0 comments on commit 9cd9e99

Please sign in to comment.