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

Commit

Permalink
Merge pull request #10 from FRC3636/cliber
Browse files Browse the repository at this point in the history
feat: climber system
  • Loading branch information
Fishhkabob authored Jan 20, 2024
2 parents 9e31924 + fcfca7d commit ab73b87
Show file tree
Hide file tree
Showing 3 changed files with 63 additions and 0 deletions.
2 changes: 2 additions & 0 deletions src/main/java/com/frcteam3636/frc2024/CAN.kt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ enum class REVMotorControllerId(val num: Int) {
OverTheBumperIntakeArm(0),
OverTheBumperIntakeFeed(0),
UnderTheBumperIntakeRoller(0),
ClimberMotor(0),

}

fun CANSparkMax(id: REVMotorControllerId, type: CANSparkLowLevel.MotorType) = CANSparkMax(id.num, type)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package com.frcteam3636.frc2024.subsystems.climber


import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj2.command.Subsystem

class Climber: Subsystem {
private var io: ClimberIO = if (RobotBase.isReal()) {
ClimberIOReal()
} else {
TODO()
}
var inputs = ClimberIO.ClimberInputs()

override fun periodic() {
io.updateInputs(inputs)
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package com.frcteam3636.frc2024.subsystems.climber

import com.frcteam3636.frc2024.can.CANSparkMax
import com.frcteam3636.frc2024.can.REVMotorControllerId
import com.revrobotics.CANSparkLowLevel
import com.revrobotics.SparkAbsoluteEncoder
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.math.util.Units
import org.littletonrobotics.junction.AutoLog

interface ClimberIO {
@AutoLog
class ClimberInputs {
var climberPosition = Rotation2d()
}

fun updateInputs(inputs: ClimberInputs)

fun moveClimber(speed: Double) {}
}
class ClimberIOReal: ClimberIO {
companion object {
const val CLIMBER_GEAR_RATIO = 1.0
}


private var climberMotor = CANSparkMax(REVMotorControllerId.ClimberMotor, CANSparkLowLevel.MotorType.kBrushless).apply{
burnFlash()
}
private val climberEncoder = climberMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle).apply {
velocityConversionFactor = Units.rotationsToRadians(1.0) * CLIMBER_GEAR_RATIO / 60
positionConversionFactor = Units.rotationsToRadians(1.0) * CLIMBER_GEAR_RATIO
}

override fun updateInputs(inputs: ClimberIO.ClimberInputs) {
inputs.climberPosition = Rotation2d(climberEncoder.position)
}


override fun moveClimber(speed: Double) {
climberMotor.set(speed)
}
}

0 comments on commit ab73b87

Please sign in to comment.