Skip to content

Commit

Permalink
feat: climb
Browse files Browse the repository at this point in the history
  • Loading branch information
Craftzman7 committed Feb 18, 2025
1 parent 3b8daac commit d6f610e
Show file tree
Hide file tree
Showing 5 changed files with 86 additions and 4 deletions.
1 change: 1 addition & 0 deletions src/main/kotlin/com/frcteam3636/frc2025/CAN.kt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ enum class CTREDeviceId(val num: Int, val bus: String) {
RightElevatorMotor(12, "*"),
ManipulatorMotor(13, "*"),
FunnelMotor(14, "*"),
ClimbMotor(15, "*"),
PigeonGyro(20, "*"),
ElevatorEncoder(30, "*"),
}
Expand Down
2 changes: 2 additions & 0 deletions src/main/kotlin/com/frcteam3636/frc2025/Robot.kt
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package com.frcteam3636.frc2025

import com.ctre.phoenix6.StatusSignal
import com.frcteam3636.frc2025.subsystems.climb.Climb
import com.frcteam3636.frc2025.subsystems.drivetrain.Drivetrain
import com.frcteam3636.frc2025.subsystems.drivetrain.poi.ReefBranchSide
import com.frcteam3636.frc2025.subsystems.elevator.Elevator
Expand Down Expand Up @@ -139,6 +140,7 @@ object Robot : LoggedRobot() {
Manipulator.register()
Elevator.register()
Funnel.register()
Climb.register()
}

/** Expose commands for autonomous routines to use and display an auto picker in Shuffleboard. */
Expand Down
40 changes: 40 additions & 0 deletions src/main/kotlin/com/frcteam3636/frc2025/subsystems/climb/Climb.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package com.frcteam3636.frc2025.subsystems.climb

import com.frcteam3636.frc2025.Robot
import edu.wpi.first.wpilibj2.command.Command
import edu.wpi.first.wpilibj2.command.Subsystem
import org.littletonrobotics.junction.Logger

object Climb : Subsystem {
private val io: ClimbIO = when (Robot.model) {
Robot.Model.SIMULATION -> TODO()
Robot.Model.COMPETITION -> ClimbIOReal()
Robot.Model.PROTOTYPE -> TODO()
}

var inputs = LoggedClimbInputs()

override fun periodic() {
io.updateInputs(inputs)
Logger.processInputs("Climb", inputs)
}

fun up(): Command = startEnd(
{
io.setSpeed(0.50)
},
{
io.setSpeed(0.0)
}
)

fun down(): Command = startEnd(
{
io.setSpeed(-0.50)
},
{
io.setSpeed(0.0)
}
)

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
package com.frcteam3636.frc2025.subsystems.climb

import com.ctre.phoenix6.configs.TalonFXConfiguration
import com.ctre.phoenix6.signals.NeutralModeValue
import com.frcteam3636.frc2025.CTREDeviceId
import com.frcteam3636.frc2025.TalonFX
import edu.wpi.first.units.Units.Amps
import org.team9432.annotation.Logged

@Logged
open class ClimbInputs {
var climberCurrent = Amps.zero()!!
}

interface ClimbIO {
fun setSpeed(percent: Double)
fun updateInputs(inputs: ClimbInputs)
}

class ClimbIOReal : ClimbIO {
private var climbMotor = TalonFX(CTREDeviceId.ClimbMotor).apply {
configurator.apply(
TalonFXConfiguration().apply {
MotorOutput.apply {
NeutralMode = NeutralModeValue.Brake
}
}
)
}

override fun setSpeed(percent: Double) {
assert(percent in -1.0..1.0)
climbMotor.set(percent)
}

override fun updateInputs(inputs: ClimbInputs) {
inputs.climberCurrent = climbMotor.supplyCurrent.value
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,17 @@ import edu.wpi.first.wpilibj.simulation.FlywheelSim
import org.team9432.annotation.Logged

@Logged
open class FunnelInputs{
open class FunnelInputs {
var rollerVelocity = RotationsPerSecond.zero()!!
var rollerCurrent = Amps.zero()!!
}

interface FunnelIO{
interface FunnelIO {
fun setSpeed(percent: Double)
fun updateInputs(inputs: FunnelInputs)
}

class FunnelIOReal : FunnelIO{
class FunnelIOReal : FunnelIO {
private var rampMotor = TalonFX(CTREDeviceId.FunnelMotor).apply {
configurator.apply(
TalonFXConfiguration().apply {
Expand Down Expand Up @@ -54,7 +54,7 @@ class FunnelIOReal : FunnelIO{
private val MOTOR_CURRENT_LIMIT = Amps.of(35.0)
}
}
class FunnelIOSim : FunnelIO{
class FunnelIOSim : FunnelIO {
private var motor = DCMotor.getKrakenX60(1)
private var system = LinearSystemId.createFlywheelSystem(motor, 1.0, 5.0)
private var simMotor = FlywheelSim(system, motor, 0.0)
Expand Down

0 comments on commit d6f610e

Please sign in to comment.