diff --git a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt b/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt index 126e75c1..a5a1a8af 100644 --- a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt +++ b/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt @@ -6,10 +6,10 @@ package com.team4099.robot2023 const val MAVEN_GROUP = "" const val MAVEN_NAME = "Crescendo-2024" const val VERSION = "unspecified" -const val GIT_REVISION = -1 -const val GIT_SHA = "UNKNOWN" -const val GIT_DATE = "UNKNOWN" -const val GIT_BRANCH = "UNKNOWN" -const val BUILD_DATE = "2023-12-16T19:11:21Z" -const val BUILD_UNIX_TIME = 1702771881467L -const val DIRTY = 129 +const val GIT_REVISION = 20 +const val GIT_SHA = "4571cd4f3189ad1982f91f7dde0d0c7d7ec30341" +const val GIT_DATE = "2024-01-12T19:01:07Z" +const val GIT_BRANCH = "intake" +const val BUILD_DATE = "2024-01-12T19:14:59Z" +const val BUILD_UNIX_TIME = 1705104899720L +const val DIRTY = 1 diff --git a/src/main/kotlin/com/team4099/robot2023/config/constants/IntakeConstants.kt b/src/main/kotlin/com/team4099/robot2023/config/constants/IntakeConstants.kt index 69610f74..3e02f6b4 100644 --- a/src/main/kotlin/com/team4099/robot2023/config/constants/IntakeConstants.kt +++ b/src/main/kotlin/com/team4099/robot2023/config/constants/IntakeConstants.kt @@ -1,12 +1,8 @@ package com.team4099.robot2023.config.constants -import com.fasterxml.jackson.annotation.JsonAutoDetect.Value -import edu.wpi.first.wpilibj.DoubleSolenoid -import org.team4099.lib.units.Fraction -import org.team4099.lib.units.Velocity import org.team4099.lib.units.base.amps -import org.team4099.lib.units.derived.* -import org.team4099.lib.units.perSecond +import org.team4099.lib.units.derived.degrees +import org.team4099.lib.units.derived.volts object IntakeConstants { val VOLTAGE_COMPENSATION = 12.0.volts @@ -16,12 +12,8 @@ object IntakeConstants { // TODO: Change gear ratio according to robot val ROLLER_CURRENT_LIMIT = 50.0.amps - val ARM_CURRENT_LIMIT = 50.0.amps const val ROLLER_MOTOR_INVERTED = true - const val ARM_MOTOR_INVERTED = false const val ROLLER_GEAR_RATIO = 36.0 / 18.0 - const val ARM_GEAR_RATIO = ((60.0 / 12.0) * (80.0 / 18.0) * (32.0 / 16.0)) - const val ARM_ENCODER_GEAR_RATIO = 36.0 / 18.0 // TODO: Update value val IDLE_ROLLER_VOLTAGE = 2.0.volts diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/Intake.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/Intake.kt index 134a693f..8f422b26 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/Intake.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/Intake.kt @@ -1,138 +1,110 @@ package com.team4099.robot2023.subsystems.intake -import com.team4099.lib.hal.Clock -import com.team4099.lib.logging.LoggedTunableNumber -import com.team4099.lib.logging.LoggedTunableValue import com.team4099.robot2023.config.constants.Constants import com.team4099.robot2023.config.constants.IntakeConstants import com.team4099.robot2023.subsystems.superstructure.Request -import edu.wpi.first.wpilibj.RobotBase import org.littletonrobotics.junction.Logger -import org.team4099.lib.controller.ArmFeedforward -import org.team4099.lib.controller.TrapezoidProfile -import org.team4099.lib.units.AngularVelocity -import org.team4099.lib.units.base.inSeconds -import org.team4099.lib.units.base.seconds -import org.team4099.lib.units.derived.Angle import org.team4099.lib.units.derived.ElectricalPotential -import org.team4099.lib.units.derived.Radian -import org.team4099.lib.units.derived.degrees -import org.team4099.lib.units.derived.inDegrees import org.team4099.lib.units.derived.inVolts -import org.team4099.lib.units.derived.inVoltsPerDegree -import org.team4099.lib.units.derived.inVoltsPerDegreePerSecond -import org.team4099.lib.units.derived.inVoltsPerDegreeSeconds -import org.team4099.lib.units.derived.perDegree -import org.team4099.lib.units.derived.perDegreePerSecond -import org.team4099.lib.units.derived.perDegreeSeconds import org.team4099.lib.units.derived.volts -import org.team4099.lib.units.inDegreesPerSecond -import org.team4099.lib.units.perSecond class Intake(private val io: IntakeIO) { - val inputs = IntakeIO.IntakeIOInputs() + val inputs = IntakeIO.IntakeIOInputs() - var rollerVoltageTarget: ElectricalPotential = 0.0.volts + var rollerVoltageTarget: ElectricalPotential = 0.0.volts - var isZeroed = false + var isZeroed = false - var lastIntakeRuntime = Clock.fpgaTime - var currentState: IntakeStake = IntakeStake.UNINITIALIZED + var currentState: IntakeStake = IntakeStake.UNINITIALIZED - var currentRequest: Request.IntakeRequest = Request.IntakeRequest.Idle() - set(value) { - rollerVoltageTarget = when (value) { - is Request.IntakeRequest.OpenLoop -> { - value.rollerVoltage - } - - is Request.IntakeRequest.Idle -> { - IntakeConstants.IDLE_ROLLER_VOLTAGE - } - } - - field = value + var currentRequest: Request.IntakeRequest = Request.IntakeRequest.Idle() + set(value) { + rollerVoltageTarget = + when (value) { + is Request.IntakeRequest.OpenLoop -> { + value.rollerVoltage + } + is Request.IntakeRequest.Idle -> { + IntakeConstants.IDLE_ROLLER_VOLTAGE + } } - private var timeProfileGeneratedAt = Clock.fpgaTime - - fun periodic() { - io.updateInputs(inputs) - - Logger.processInputs("GroundIntake", inputs) + field = value + } - Logger.recordOutput("GroundIntake/currentState", currentState.name) + fun periodic() { + io.updateInputs(inputs) - Logger.recordOutput("GroundIntake/requestedState", currentRequest.javaClass.simpleName) + Logger.processInputs("Intake", inputs) - Logger.recordOutput("GroundIntake/isZeroed", isZeroed) + Logger.recordOutput("Intake/currentState", currentState.name) - if (Constants.Tuning.DEBUGING_MODE) { - Logger.recordOutput("GroundIntake/isAtCommandedState", currentState.equivalentToRequest(currentRequest)) + Logger.recordOutput("Intake/requestedState", currentRequest.javaClass.simpleName) - Logger.recordOutput("GroundIntake/timeProfileGeneratedAt", timeProfileGeneratedAt.inSeconds) + Logger.recordOutput("Intake/isZeroed", isZeroed) - Logger.recordOutput("GroundIntake/rollerVoltageTarget", rollerVoltageTarget.inVolts) - } + if (Constants.Tuning.DEBUGING_MODE) { + Logger.recordOutput( + "Intake/isAtCommandedState", currentState.equivalentToRequest(currentRequest) + ) - var nextState = currentState - when (currentState) { - IntakeStake.UNINITIALIZED -> { - // Outputs - // No designated output functionality because targeting position will take care of it next - // loop cycle - - // Transitions - nextState = IntakeStake.IDLE - } - IntakeStake.IDLE -> { - setRollerVoltage(IntakeConstants.IDLE_ROLLER_VOLTAGE) - - // Transitions - nextState = fromRequestToState(currentRequest) - } - IntakeStake.OPEN_LOOP_REQUEST -> { - setRollerVoltage(rollerVoltageTarget) - - // Transitions - nextState = fromRequestToState(currentRequest) - } - } - - // The next loop cycle, we want to run ground intake at the state that was requested. setting - // current state to the next state ensures that we run the logic for the state we want in the - // next loop cycle. - currentState = nextState + Logger.recordOutput("Intake/rollerVoltageTarget", rollerVoltageTarget.inVolts) } - /** @param appliedVoltage Represents the applied voltage of the roller motor */ - fun setRollerVoltage(appliedVoltage: ElectricalPotential) { - io.setRollerVoltage(appliedVoltage) + var nextState = currentState + when (currentState) { + IntakeStake.UNINITIALIZED -> { + // Outputs + // No designated output functionality because targeting position will take care of it next + // loop cycle + + // Transitions + nextState = IntakeStake.IDLE + } + IntakeStake.IDLE -> { + setRollerVoltage(IntakeConstants.IDLE_ROLLER_VOLTAGE) + + // Transitions + nextState = fromRequestToState(currentRequest) + } + IntakeStake.OPEN_LOOP -> { + setRollerVoltage(rollerVoltageTarget) + + // Transitions + nextState = fromRequestToState(currentRequest) + } } - fun zeroArm() { - io.zeroEncoder() + // The next loop cycle, we want to run ground intake at the state that was requested. setting + // current state to the next state ensures that we run the logic for the state we want in the + // next loop cycle. + currentState = nextState + } + + /** @param appliedVoltage Represents the applied voltage of the roller motor */ + fun setRollerVoltage(appliedVoltage: ElectricalPotential) { + io.setRollerVoltage(appliedVoltage) + } + + companion object { + enum class IntakeStake { + UNINITIALIZED, + IDLE, + OPEN_LOOP; + + inline fun equivalentToRequest(request: Request.IntakeRequest): Boolean { + return ( + (request is Request.IntakeRequest.OpenLoop && this == OPEN_LOOP) || + (request is Request.IntakeRequest.Idle && this == IDLE) + ) + } } - companion object { - enum class IntakeStake { - UNINITIALIZED, - IDLE, - OPEN_LOOP_REQUEST; - - inline fun equivalentToRequest(request: Request.IntakeRequest): Boolean { - return ( - (request is Request.IntakeRequest.OpenLoop && this == OPEN_LOOP_REQUEST) || - (request is Request.IntakeRequest.Idle && this == IDLE) - ) - } - } - - inline fun fromRequestToState(request: Request.IntakeRequest): IntakeStake { - return when (request) { - is Request.IntakeRequest.OpenLoop -> IntakeStake.OPEN_LOOP_REQUEST - is Request.IntakeRequest.Idle -> IntakeStake.IDLE - } - } + inline fun fromRequestToState(request: Request.IntakeRequest): IntakeStake { + return when (request) { + is Request.IntakeRequest.OpenLoop -> IntakeStake.OPEN_LOOP + is Request.IntakeRequest.Idle -> IntakeStake.IDLE + } } + } } diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIO.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIO.kt index 1c5099f3..91cdee66 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIO.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIO.kt @@ -6,19 +6,10 @@ import org.team4099.lib.units.base.amps import org.team4099.lib.units.base.celsius import org.team4099.lib.units.base.inAmperes import org.team4099.lib.units.base.inCelsius -import org.team4099.lib.units.derived.Angle -import org.team4099.lib.units.derived.DerivativeGain import org.team4099.lib.units.derived.ElectricalPotential -import org.team4099.lib.units.derived.IntegralGain -import org.team4099.lib.units.derived.ProportionalGain -import org.team4099.lib.units.derived.Radian -import org.team4099.lib.units.derived.Volt -import org.team4099.lib.units.derived.degrees -import org.team4099.lib.units.derived.inDegrees import org.team4099.lib.units.derived.inVolts import org.team4099.lib.units.derived.rotations import org.team4099.lib.units.derived.volts -import org.team4099.lib.units.inDegreesPerSecond import org.team4099.lib.units.inRotationsPerMinute import org.team4099.lib.units.perMinute import org.team4099.lib.units.perSecond @@ -32,25 +23,10 @@ interface IntakeIO { var rollerStatorCurrent = 0.0.amps var rollerTemp = 0.0.celsius - var armPosition = 0.0.degrees - var armVelocity = 0.0.degrees.perSecond - var armAbsoluteEncoderPosition = 0.0.degrees - - var armAppliedVoltage = 0.0.volts - var armSupplyCurrent = 0.0.amps - var armStatorCurrent = 0.0.amps - var armTemp = 0.0.celsius - var isSimulated = false override fun toLog(table: LogTable?) { - table?.put("armPositionDegrees", armPosition.inDegrees) - table?.put("armAbsoluteEncoderPositionDegrees", armAbsoluteEncoderPosition.inDegrees) - table?.put("armVelocityDegreesPerSec", armVelocity.inDegreesPerSecond) - table?.put("armAppliedVoltage", armAppliedVoltage.inVolts) - table?.put("armSupplyCurrentAmps", armSupplyCurrent.inAmperes) - table?.put("armStatorCurrentAmps", armStatorCurrent.inAmperes) - table?.put("armTempCelsius", armTemp.inCelsius) + table?.put("isSimulated", isSimulated) table?.put("rollerVelocityRPM", rollerVelocity.inRotationsPerMinute) table?.put("rollerAppliedVoltage", rollerAppliedVoltage.inVolts) @@ -60,30 +36,6 @@ interface IntakeIO { } override fun fromLog(table: LogTable?) { - table?.get("armPositionDegrees", armPosition.inDegrees)?.let { armPosition = it.degrees } - - table?.get("armAbsoluteEncoderPositionDegrees", armAbsoluteEncoderPosition.inDegrees)?.let { - armAbsoluteEncoderPosition = it.degrees - } - - table?.get("armVelocityDegreesPerSec", armVelocity.inDegreesPerSecond)?.let { - armVelocity = it.degrees.perSecond - } - - table?.get("armAppliedVoltage", armAppliedVoltage.inVolts)?.let { - armAppliedVoltage = it.volts - } - - table?.get("armSupplyCurrentAmps", armSupplyCurrent.inAmperes)?.let { - armSupplyCurrent = it.amps - } - - table?.get("armStatorCurrentAmps", armStatorCurrent.inAmperes)?.let { - armStatorCurrent = it.amps - } - - table?.get("armTempCelsius", armTemp.inCelsius)?.let { armTemp = it.celsius } - table?.get("rollerVelocityRPM", rollerVelocity.inRotationsPerMinute)?.let { rollerVelocity = it.rotations.perSecond } @@ -104,31 +56,9 @@ interface IntakeIO { } } - fun updateInputs(io: IntakeIOInputs) {} - - fun setRollerVoltage(voltage: ElectricalPotential) {} - - fun setArmVoltage(voltage: ElectricalPotential) {} - - fun setArmPosition(armPosition: Angle, feedforward: ElectricalPotential) {} - - /** - * Updates the PID constants using the implementation controller - * - * @param kP accounts for linear error - * @param kI accounts for integral error - * @param kD accounts for derivative error - */ - fun configPID( - kP: ProportionalGain, - kI: IntegralGain, - kD: DerivativeGain - ) {} - - /** Sets the current encoder position to be the zero value */ - fun zeroEncoder() {} + fun updateInputs(io: IntakeIOInputs) - fun setRollerBrakeMode(brake: Boolean) {} + fun setRollerVoltage(voltage: ElectricalPotential) - fun setArmBrakeMode(brake: Boolean) + fun setRollerBrakeMode(brake: Boolean) } diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIONEO.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIONEO.kt index 103faf83..dadcd0db 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIONEO.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIONEO.kt @@ -2,82 +2,31 @@ package com.team4099.robot2023.subsystems.intake import com.revrobotics.CANSparkMax import com.revrobotics.CANSparkMaxLowLevel -import com.revrobotics.SparkMaxPIDController import com.team4099.lib.math.clamp import com.team4099.robot2023.config.constants.Constants import com.team4099.robot2023.config.constants.IntakeConstants import com.team4099.robot2023.subsystems.falconspin.MotorChecker import com.team4099.robot2023.subsystems.falconspin.MotorCollection import com.team4099.robot2023.subsystems.falconspin.Neo -import edu.wpi.first.wpilibj.DutyCycleEncoder import org.littletonrobotics.junction.Logger import org.team4099.lib.units.base.amps import org.team4099.lib.units.base.celsius import org.team4099.lib.units.base.inAmperes -import org.team4099.lib.units.derived.Angle -import org.team4099.lib.units.derived.DerivativeGain import org.team4099.lib.units.derived.ElectricalPotential -import org.team4099.lib.units.derived.IntegralGain -import org.team4099.lib.units.derived.ProportionalGain -import org.team4099.lib.units.derived.Radian -import org.team4099.lib.units.derived.Volt -import org.team4099.lib.units.derived.degrees -import org.team4099.lib.units.derived.inDegrees import org.team4099.lib.units.derived.inVolts -import org.team4099.lib.units.derived.rotations import org.team4099.lib.units.derived.volts import org.team4099.lib.units.sparkMaxAngularMechanismSensor -import kotlin.math.IEEErem import kotlin.math.absoluteValue object IntakeIONEO : IntakeIO { private val rollerSparkMax = CANSparkMax(Constants.Intake.ROLLER_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless) - private val armSparkMax = - CANSparkMax(Constants.Intake.ARM_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless) - private val rollerSensor = sparkMaxAngularMechanismSensor( rollerSparkMax, IntakeConstants.ROLLER_GEAR_RATIO, IntakeConstants.VOLTAGE_COMPENSATION ) - private val armSensor = - sparkMaxAngularMechanismSensor( - armSparkMax, IntakeConstants.ARM_GEAR_RATIO, IntakeConstants.VOLTAGE_COMPENSATION - ) - - private val armEncoder = armSparkMax.encoder - - private val throughBoreEncoder = DutyCycleEncoder(Constants.Intake.REV_ENCODER_PORT) - - private val armPIDController: SparkMaxPIDController = armSparkMax.pidController - - // gets the reported angle from the through bore encoder - private val encoderAbsolutePosition: Angle - get() { - var output = - ( - (-throughBoreEncoder.absolutePosition.rotations) * - IntakeConstants.ARM_ENCODER_GEAR_RATIO - ) - - if (output in (-55).degrees..0.0.degrees) { - output -= 180.degrees - } - - return output - } - - // uses the absolute encoder position to calculate the arm position - private val armAbsolutePosition: Angle - get() { - return (encoderAbsolutePosition - IntakeConstants.ABSOLUTE_ENCODER_OFFSET).inDegrees.IEEErem( - 360.0 - ) - .degrees - } - init { rollerSparkMax.restoreFactoryDefaults() rollerSparkMax.clearFaults() @@ -91,16 +40,6 @@ object IntakeIONEO : IntakeIO { rollerSparkMax.openLoopRampRate = 0.0 rollerSparkMax.burnFlash() - armSparkMax.restoreFactoryDefaults() - armSparkMax.clearFaults() - - armSparkMax.enableVoltageCompensation(IntakeConstants.VOLTAGE_COMPENSATION.inVolts) - armSparkMax.setSmartCurrentLimit(IntakeConstants.ARM_CURRENT_LIMIT.inAmperes.toInt()) - armSparkMax.inverted = IntakeConstants.ARM_MOTOR_INVERTED - armSparkMax.idleMode = CANSparkMax.IdleMode.kBrake - - armSparkMax.burnFlash() - MotorChecker.add( "Ground Intake", "Roller", @@ -112,18 +51,6 @@ object IntakeIONEO : IntakeIO { 90.celsius ), ) - - MotorChecker.add( - "Ground Intake", - "Pivot", - MotorCollection( - mutableListOf(Neo(armSparkMax, "Pivot Motor")), - IntakeConstants.ARM_CURRENT_LIMIT, - 70.celsius, - IntakeConstants.ARM_CURRENT_LIMIT - 30.amps, - 90.celsius - ) - ) } override fun updateInputs(inputs: IntakeIO.IntakeIOInputs) { @@ -139,30 +66,11 @@ object IntakeIONEO : IntakeIO { inputs.rollerStatorCurrent * rollerSparkMax.appliedOutput.absoluteValue inputs.rollerTemp = rollerSparkMax.motorTemperature.celsius - inputs.armPosition = armSensor.position - inputs.armAbsoluteEncoderPosition = armAbsolutePosition - inputs.armVelocity = armSensor.velocity - inputs.armAppliedVoltage = armSparkMax.busVoltage.volts * armSparkMax.appliedOutput - inputs.armStatorCurrent = armSparkMax.outputCurrent.amps - inputs.armTemp = armSparkMax.motorTemperature.celsius - - // same math as rollersupplycurrent - inputs.armSupplyCurrent = inputs.armStatorCurrent * armSparkMax.appliedOutput.absoluteValue - - Logger.recordOutput( - "GroundIntake/absoluteEncoderPositionDegrees", encoderAbsolutePosition.inDegrees - ) - Logger.recordOutput( - "GroundIntake/rollerMotorOvercurrentFault", + "Intake/rollerMotorOvercurrentFault", rollerSparkMax.getFault(CANSparkMax.FaultID.kOvercurrent) ) - Logger.recordOutput("GroundIntake/busVoltage", rollerSparkMax.busVoltage) - - Logger.recordOutput( - "GroundIntake/armSensorVelocity", - armSparkMax.encoder.velocity * IntakeConstants.ARM_GEAR_RATIO - ) + Logger.recordOutput("Intake/busVoltage", rollerSparkMax.busVoltage) } /** @@ -177,57 +85,6 @@ object IntakeIONEO : IntakeIO { ) } - /** - * Sets the arm motor voltage, ensures the voltage is limited to battery voltage compensation - * - * @param voltage the voltage to set the arm motor to - */ - override fun setArmVoltage(voltage: ElectricalPotential) { - armSparkMax.setVoltage(voltage.inVolts) - - Logger.recordOutput("GroundIntake/commandedVoltage", voltage.inVolts) - } - - /** - * Sets the arm to a desired angle, uses feedforward to account for external forces in the system - * The armPIDController uses the previously set PID constants and ff to calculate how to get to - * the desired position - * - * @param armPosition the desired angle to set the aerm to - * @param feedforward the amount of volts to apply for feedforward - */ - override fun setArmPosition(armPosition: Angle, feedforward: ElectricalPotential) { - armPIDController.setReference( - armSensor.positionToRawUnits(armPosition), - CANSparkMax.ControlType.kPosition, - 0, - feedforward.inVolts - ) - } - - /** - * Updates the PID constants using the implementation controller, uses arm sensor to convert from - * PID constants to motor controller units - * - * @param kP accounts for linear error - * @param kI accounts for integral error - * @param kD accounts for derivative error - */ - override fun configPID( - kP: ProportionalGain, - kI: IntegralGain, - kD: DerivativeGain - ) { - armPIDController.p = armSensor.proportionalPositionGainToRawUnits(kP) - armPIDController.i = armSensor.integralPositionGainToRawUnits(kI) - armPIDController.d = armSensor.derivativePositionGainToRawUnits(kD) - } - - /** recalculates the current position of the neo encoder using value from the absolute encoder */ - override fun zeroEncoder() { - armEncoder.position = armSensor.positionToRawUnits(armAbsolutePosition) - } - /** * Sets the roller motor brake mode * @@ -240,17 +97,4 @@ object IntakeIONEO : IntakeIO { rollerSparkMax.idleMode = CANSparkMax.IdleMode.kCoast } } - - /** - * Sets the arm motor brake mode - * - * @param brake if it brakes - */ - override fun setArmBrakeMode(brake: Boolean) { - if (brake) { - rollerSparkMax.idleMode = CANSparkMax.IdleMode.kBrake - } else { - rollerSparkMax.idleMode = CANSparkMax.IdleMode.kCoast - } - } } 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 c95979b3..0f144610 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/superstructure/Request.kt @@ -7,7 +7,6 @@ import org.team4099.lib.units.AngularVelocity import org.team4099.lib.units.LinearVelocity import org.team4099.lib.units.base.Length import org.team4099.lib.units.base.inches -import org.team4099.lib.units.derived.Angle import org.team4099.lib.units.derived.ElectricalPotential import org.team4099.lib.units.perSecond @@ -60,10 +59,8 @@ sealed interface Request { } sealed interface IntakeRequest : Request { - class OpenLoop(val rollerVoltage: ElectricalPotential) : - IntakeRequest - class Idle() : - IntakeRequest + class OpenLoop(val rollerVoltage: ElectricalPotential) : IntakeRequest + class Idle() : IntakeRequest } sealed interface DrivetrainRequest : Request {