From ffd79239856844cf4b852153da0e5774e24647a9 Mon Sep 17 00:00:00 2001 From: 00magikarp <94652654+00magikarp@users.noreply.github.com> Date: Tue, 23 Jan 2024 18:50:56 -0500 Subject: [PATCH] completed saraansh's peer review --- .../robot2023/subsystems/feeder/Feeder.kt | 22 +++++-------------- .../robot2023/subsystems/feeder/FeederIO.kt | 2 ++ .../subsystems/feeder/FeederIONeo.kt | 8 +------ .../subsystems/superstructure/Request.kt | 1 - 4 files changed, 8 insertions(+), 25 deletions(-) diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/Feeder.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/Feeder.kt index 026f7be6..3fe709cb 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/Feeder.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/Feeder.kt @@ -65,28 +65,19 @@ class Feeder(val io: FeederIO) : SubsystemBase() { var nextState = currentState when (currentState) { FeederStates.UNINITIALIZED -> { - nextState = FeederStates.IDLE - } - FeederStates.IDLE -> { - setFeederVoltage(FeederConstants.FEEDER_IDLE_VOLTAGE) - nextState = fromRequestToState(currentRequest) + nextState = FeederStates.OPEN_LOOP_INTAKE } FeederStates.OPEN_LOOP_INTAKE -> { - if (!hasNote) { setFeederVoltage(feederTargetVoltage) - nextState = fromRequestToState(currentRequest) - } else { - nextState = FeederStates.IDLE - } + } + nextState = fromRequestToState(currentRequest) } FeederStates.OPEN_LOOP_SHOOT -> { if (hasNote) { setFeederVoltage(feederTargetVoltage) - nextState = fromRequestToState(currentRequest) - } else { - nextState = FeederStates.IDLE } + nextState = fromRequestToState(currentRequest) } } currentState = nextState @@ -112,22 +103,19 @@ class Feeder(val io: FeederIO) : SubsystemBase() { companion object { enum class FeederStates { UNINITIALIZED, - IDLE, OPEN_LOOP_INTAKE, OPEN_LOOP_SHOOT; fun equivalentToRequest(request: Request.FeederRequest): Boolean { return ( (request is Request.FeederRequest.OpenLoopIntake && this == OPEN_LOOP_SHOOT) || - (request is Request.FeederRequest.OpenLoopIntake && this == OPEN_LOOP_INTAKE) || - (request is Request.FeederRequest.Idle && this == IDLE) + (request is Request.FeederRequest.OpenLoopIntake && this == OPEN_LOOP_INTAKE) ) } } fun fromRequestToState(request: Request.FeederRequest): FeederStates { return when (request) { - is Request.FeederRequest.Idle -> FeederStates.IDLE is Request.FeederRequest.OpenLoopIntake -> FeederStates.OPEN_LOOP_INTAKE is Request.FeederRequest.OpenLoopShoot -> FeederStates.OPEN_LOOP_SHOOT } diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIO.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIO.kt index 9464277b..00fafbbf 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIO.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIO.kt @@ -33,6 +33,7 @@ interface FeederIO { table?.put("feederStatorCurrent", feederStatorCurrent.inAmperes) table?.put("feederSupplyCurrent", feederSupplyCurrent.inAmperes) table?.put("feederTempCelcius", feederTemp.inCelsius) + table?.put("feederBeamBroken", beamBroken) } override fun fromLog(table: LogTable?) { @@ -53,6 +54,7 @@ interface FeederIO { } table?.get("feederTempCelcius", feederTemp.inCelsius)?.let { feederTemp = it.celsius } + table?.get("feederBeamBroken", beamBroken)?.let { beamBroken = it } } } diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIONeo.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIONeo.kt index 380d625b..80c437a0 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIONeo.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/feeder/FeederIONeo.kt @@ -37,7 +37,6 @@ object FeederIONeo : FeederIO { feederSparkMax.idleMode = CANSparkMax.IdleMode.kCoast - feederSparkMax.openLoopRampRate = 0.0 feederSparkMax.burnFlash() MotorChecker.add( @@ -47,7 +46,7 @@ object FeederIONeo : FeederIO { mutableListOf(Neo(feederSparkMax, "Roller Motor")), FeederConstants.FEEDER_CURRENT_LIMIT, 70.celsius, - FeederConstants.FEEDER_CURRENT_LIMIT - 0.amps, + 30.amps, 90.celsius ), ) @@ -66,11 +65,6 @@ object FeederIONeo : FeederIO { inputs.feederStatorCurrent * feederSparkMax.appliedOutput.absoluteValue inputs.feederTemp = feederSparkMax.motorTemperature.celsius - Logger.recordOutput( - "Intake/rollerMotorOvercurrentFault", - feederSparkMax.getFault(CANSparkMax.FaultID.kOvercurrent) - ) - Logger.recordOutput("Intake/busVoltage", feederSparkMax.busVoltage) } /** diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt index fc1afc4e..6c8b29bd 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt @@ -28,7 +28,6 @@ sealed interface Request { } sealed interface FeederRequest : Request { - class Idle() : FeederRequest class OpenLoopIntake(val feederVoltage: ElectricalPotential) : FeederRequest class OpenLoopShoot(val feederVoltage: ElectricalPotential) : FeederRequest }