diff --git a/.run/Build & Deploy Robot for Debugging.run.xml b/.run/Build & Deploy Robot for Debugging.run.xml index 0fa85ce..2a40583 100644 --- a/.run/Build & Deploy Robot for Debugging.run.xml +++ b/.run/Build & Deploy Robot for Debugging.run.xml @@ -87,4 +87,26 @@ false + + + + + + true + true + false + false + + \ No newline at end of file diff --git a/.run/Build & Deploy Robot.run.xml b/.run/Build & Deploy Robot.run.xml index 89430c8..88cc1c1 100644 --- a/.run/Build & Deploy Robot.run.xml +++ b/.run/Build & Deploy Robot.run.xml @@ -18,7 +18,7 @@ true true false - false + false @@ -40,7 +40,7 @@ true true false - false + false @@ -62,7 +62,7 @@ true true false - false + false @@ -84,7 +84,29 @@ true true false - false + false + + + + + + + + true + true + false + false \ No newline at end of file diff --git a/.run/Build Robot.run.xml b/.run/Build Robot.run.xml index 6b0d2ec..471f682 100644 --- a/.run/Build Robot.run.xml +++ b/.run/Build Robot.run.xml @@ -87,4 +87,26 @@ false + + + + + + true + true + false + false + + \ No newline at end of file diff --git a/.run/Clean Build & Deploy Robot for Debugging.run.xml b/.run/Clean Build & Deploy Robot for Debugging.run.xml index 4e4b2d3..8a73c3c 100644 --- a/.run/Clean Build & Deploy Robot for Debugging.run.xml +++ b/.run/Clean Build & Deploy Robot for Debugging.run.xml @@ -91,4 +91,27 @@ false + + + + + + true + true + false + false + + \ No newline at end of file diff --git a/.run/Clean Build & Deploy Robot.run.xml b/.run/Clean Build & Deploy Robot.run.xml index d38efbe..e4441b2 100644 --- a/.run/Clean Build & Deploy Robot.run.xml +++ b/.run/Clean Build & Deploy Robot.run.xml @@ -91,4 +91,27 @@ false + + + + + + true + true + false + false + + \ No newline at end of file diff --git a/.run/Clean Build Robot.run.xml b/.run/Clean Build Robot.run.xml index 3899e9e..e43dd4a 100644 --- a/.run/Clean Build Robot.run.xml +++ b/.run/Clean Build Robot.run.xml @@ -19,7 +19,7 @@ true true false - false + false @@ -42,7 +42,7 @@ true true false - false + false @@ -65,7 +65,7 @@ true true false - false + false @@ -88,7 +88,7 @@ true true false - false + false @@ -111,7 +111,7 @@ true true false - false + false @@ -134,7 +134,7 @@ true true false - false + false @@ -157,7 +157,7 @@ true true false - false + false @@ -180,7 +180,30 @@ true true false - false + false + + + + + + + + true + true + false + false \ No newline at end of file diff --git a/.run/Clean.run.xml b/.run/Clean.run.xml index 5ffb2e5..2300853 100644 --- a/.run/Clean.run.xml +++ b/.run/Clean.run.xml @@ -87,4 +87,26 @@ false + + + + + + true + true + false + false + + \ No newline at end of file diff --git a/build.gradle b/build.gradle index 622c04f..3107c8e 100644 --- a/build.gradle +++ b/build.gradle @@ -4,7 +4,7 @@ plugins { id "java" id "idea" id "org.jetbrains.kotlin.jvm" version "1.8.20" - id "edu.wpi.first.GradleRIO" version "2024.1.1" + id "edu.wpi.first.GradleRIO" version "2024.2.1" id "org.jlleitschuh.gradle.ktlint" version "11.6.1" id "org.jetbrains.dokka" version "1.8.10" } diff --git a/src/main/kotlin/frc/team449/RobotLoop.kt b/src/main/kotlin/frc/team449/RobotLoop.kt index 41febb8..7b166c6 100644 --- a/src/main/kotlin/frc/team449/RobotLoop.kt +++ b/src/main/kotlin/frc/team449/RobotLoop.kt @@ -26,7 +26,7 @@ import monologue.Monologue import org.littletonrobotics.urcl.URCL import kotlin.jvm.optionals.getOrNull -/** The main class of the robot, constructs all the subsystems and initializes default commands. */ +/** The main class of the robot, constructs all the subsystems and initializes default commands . */ class RobotLoop : TimedRobot(), Logged { @Log.NT @@ -41,6 +41,7 @@ class RobotLoop : TimedRobot(), Logged { private var routineMap = hashMapOf() private val controllerBinder = ControllerBindings(robot.driveController, robot.mechController, robot) + override fun robotInit() { // Yes this should be a print statement, it's useful to know that robotInit started. println("Started robotInit.") diff --git a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/FeederConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/FeederConstants.kt new file mode 100644 index 0000000..32e4c9b --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/FeederConstants.kt @@ -0,0 +1,12 @@ +package frc.team449.robot2024.constants.subsystem + +object FeederConstants { + const val MOTOR_ID = 7 + const val FOLLOLWER_ID = 55 + const val FOLLOWER_INV = false + const val INVERTED = true + const val CURRENT_LIM = 15 + + const val INTAKE_VOLTAGE = 8.0 + const val REVERSE_VOLTAGE = -5.0 +} diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/Feeder.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/Feeder.kt new file mode 100644 index 0000000..9929842 --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/Feeder.kt @@ -0,0 +1,57 @@ +package frc.team449.robot2024.subsystems + +import com.revrobotics.CANSparkMax +import edu.wpi.first.util.sendable.SendableBuilder +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.SubsystemBase +import frc.team449.robot2024.constants.subsystem.FeederConstants +import frc.team449.system.encoder.NEOEncoder +import frc.team449.system.motor.WrappedMotor +import frc.team449.system.motor.createSparkMax + +class Feeder( + val motor: WrappedMotor +) : SubsystemBase() { + + fun intake(): Command { + return this.runOnce { + motor.setVoltage(FeederConstants.INTAKE_VOLTAGE) + motor.stopMotor(); + } + } + + fun outtake(): Command { + return this.runOnce { + motor.setVoltage(FeederConstants.REVERSE_VOLTAGE) + } + } + + fun stop(): Command { + return this.runOnce { + motor.stopMotor() + } + } + + override fun initSendable(builder: SendableBuilder) { + builder.publishConstString("1.0", "Motor Voltages") + builder.addDoubleProperty("1.1 Last Voltage", { motor.lastVoltage }, null) + } + + companion object { + fun createProtoUndertaker(): Feeder { + val motor = createSparkMax( + "ProtoUndertaker Motor", + FeederConstants.MOTOR_ID, + NEOEncoder.creator( + 1.0, + 1.0 + ), + inverted = FeederConstants.INVERTED, + currentLimit = FeederConstants.CURRENT_LIM, + slaveSparks = mapOf(Pair(FeederConstants.FOLLOLWER_ID, FeederConstants.FOLLOWER_INV)) + ) + + return Feeder(motor) + } + } +}