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

Commit

Permalink
indexer sim
Browse files Browse the repository at this point in the history
  • Loading branch information
NikolaJenkins committed Nov 21, 2024
1 parent af788c7 commit b994c72
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 6 deletions.
Original file line number Diff line number Diff line change
@@ -1,12 +1,17 @@
package com.frcteam3636.frc2024.subsystems.indexer

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

object Indexer: Subsystem {
private var io: IndexerIO = IndexerIOReal()
private var io: IndexerIO = when (Robot.model) {
Robot.Model.SIMULATION -> IndexerIOSim()
Robot.Model.COMPETITION -> IndexerIOReal()
Robot.Model.PROTOTYPE -> IndexerIOPrototype()
}

var inputs = IndexerIO.Inputs()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ import com.frcteam3636.frc2024.Robot
import com.frcteam3636.frc2024.utils.LimelightHelpers
import com.revrobotics.CANSparkLowLevel
import edu.wpi.first.math.system.plant.DCMotor
import edu.wpi.first.units.Units.RadiansPerSecond
import edu.wpi.first.units.Units.RotationsPerSecond
import edu.wpi.first.wpilibj.simulation.FlywheelSim

public enum class BalloonState {
Expand All @@ -19,7 +21,7 @@ public enum class BalloonState {

interface IndexerIO {
class Inputs : LoggableInputs {
var indexerVelocity = Rotation2d()
var indexerVelocity = RotationsPerSecond.zero()
var indexerCurrent: Double = 0.0
var balloonState: BalloonState = BalloonState.None

Expand All @@ -30,7 +32,7 @@ interface IndexerIO {
}

override fun fromLog(table: LogTable) {
indexerVelocity = table.get("Indexer Velocity", indexerVelocity)!![0]
indexerVelocity = table.get("Indexer Velocity", indexerVelocity)!!
indexerCurrent = table.get("Indexer Wheel Current", indexerCurrent)
balloonState = table.get("Balloon Color", balloonState)
}
Expand All @@ -55,7 +57,7 @@ class IndexerIOReal : IndexerIO{
)

override fun updateInputs(inputs: IndexerIO.Inputs) {
inputs.indexerVelocity = Rotation2d(indexerMotor.encoder.velocity)
inputs.indexerVelocity = RadiansPerSecond.of(indexerMotor.encoder.velocity)
inputs.indexerCurrent = indexerMotor.outputCurrent

when (val colorClass = LimelightHelpers.getClassifierClass("limelight-sensor")) {
Expand All @@ -81,11 +83,20 @@ class IndexerIOSim: IndexerIO {

override fun updateInputs(inputs: IndexerIO.Inputs) {
flywheelSim.update(Robot.period)
inputs.indexerVelocity = flywheelSim.angularVelocityRadPerSec
inputs.indexerVelocity = RadiansPerSecond.of(flywheelSim.angularVelocityRadPerSec)
}

override fun setSpinSpeed(speed: Double) {
assert(speed in -1.0..1.0)
flywheelSim.setInputVoltage(speed*12.0)
}
}

class IndexerIOPrototype: IndexerIO {
override fun updateInputs(inputs: IndexerIO.Inputs) {
}

override fun setSpinSpeed(speed: Double) {
TODO("Not yet implemented")
}

}

0 comments on commit b994c72

Please sign in to comment.