Skip to content

Commit

Permalink
spotlessApply
Browse files Browse the repository at this point in the history
  • Loading branch information
MatthewChoulas committed Jan 28, 2024
1 parent e15f527 commit 8c154f7
Show file tree
Hide file tree
Showing 18 changed files with 230 additions and 259 deletions.
18 changes: 9 additions & 9 deletions src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@ import org.team4099.lib.units.perSecond
import com.ctre.phoenix6.controls.PositionVoltage as PositionVoltagePhoenix6

class PositionVoltage(

private var position: Angle, // Assuming an AngularPosition type exists similar to AngularVelocity
private var enableFOC: Boolean = true,
private var feedforward: ElectricalPotential = 0.0.volts,
private var slot: Int = 0,
private var overrideBrakeDurNeutral: Boolean = false,
private var limitForwardMotion: Boolean = false,
private var limitReverseMotion: Boolean = false,
private var velocity: AngularVelocity = 0.0.degrees.perSecond,
private var position:
Angle, // Assuming an AngularPosition type exists similar to AngularVelocity
private var enableFOC: Boolean = true,
private var feedforward: ElectricalPotential = 0.0.volts,
private var slot: Int = 0,
private var overrideBrakeDurNeutral: Boolean = false,
private var limitForwardMotion: Boolean = false,
private var limitReverseMotion: Boolean = false,
private var velocity: AngularVelocity = 0.0.degrees.perSecond,
) {

val positionVoltagePhoenix6 =
Expand Down
6 changes: 3 additions & 3 deletions src/main/kotlin/com/team4099/robot2023/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@ import com.team4099.robot2023.subsystems.drivetrain.drive.Drivetrain
import com.team4099.robot2023.subsystems.drivetrain.drive.DrivetrainIO
import com.team4099.robot2023.subsystems.drivetrain.drive.DrivetrainIOSim
import com.team4099.robot2023.subsystems.drivetrain.gyro.GyroIO
import com.team4099.robot2023.subsystems.feeder.Feeder
import com.team4099.robot2023.subsystems.feeder.FeederIONeo
import com.team4099.robot2023.subsystems.feeder.FeederIOSim
import com.team4099.robot2023.subsystems.elevator.Elevator
import com.team4099.robot2023.subsystems.elevator.ElevatorIONEO
import com.team4099.robot2023.subsystems.elevator.ElevatorIOSim
import com.team4099.robot2023.subsystems.feeder.Feeder
import com.team4099.robot2023.subsystems.feeder.FeederIONeo
import com.team4099.robot2023.subsystems.feeder.FeederIOSim
import com.team4099.robot2023.subsystems.limelight.LimelightVision
import com.team4099.robot2023.subsystems.limelight.LimelightVisionIO
import com.team4099.robot2023.subsystems.vision.Vision
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@ import com.team4099.lib.trajectory.CustomTrajectoryGenerator
import com.team4099.lib.trajectory.Waypoint
import com.team4099.robot2023.config.constants.DrivetrainConstants
import com.team4099.robot2023.subsystems.drivetrain.drive.Drivetrain
<<<<<<< HEAD
import com.team4099.robot2023.subsystems.superstructure.Request.DrivetrainRequest
=======
>>>>>>> elevator
import com.team4099.robot2023.util.AllianceFlipUtil
import com.team4099.robot2023.util.Velocity2d
import edu.wpi.first.math.kinematics.ChassisSpeeds
Expand Down
12 changes: 0 additions & 12 deletions src/main/kotlin/com/team4099/robot2023/config/ControlBoard.kt
Original file line number Diff line number Diff line change
Expand Up @@ -96,16 +96,4 @@ object ControlBoard {
val characterizeIntake = Trigger { technician.xButton }

// for testing
val setArmCommand = Trigger { technician.yButton }

<<<<<<< HEAD
val feederIntakeTest = Trigger { driver.aButton }
val feederShootTest = Trigger { driver.bButton }
=======
val elevatorOpenLoopExtend = Trigger { driver.aButton }
val elevatorOpenLoopRetract = Trigger { driver.bButton }
val elevatorClosedLoopHigh = Trigger { driver.xButton }
val elevatorClosedLoopLow = Trigger { driver.yButton }
>>>>>>> elevator
}

Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@ import org.team4099.lib.units.base.Meter
import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.base.percent
import org.team4099.lib.units.base.pounds
import org.team4099.lib.units.base.seconds
import org.team4099.lib.units.derived.DerivativeGain
Expand Down Expand Up @@ -56,7 +55,6 @@ object ElevatorConstants {
val ELEVATOR_OPEN_LOOP_SOFT_LIMIT_RETRACTION = 0.0.inches
val ELEVATOR_SAFE_THRESHOLD = 5.0.inches


val ELEVATOR_TOLERANCE = 0.2.inches

val MAX_VELOCITY = 0.82.meters.perSecond
Expand Down Expand Up @@ -84,5 +82,4 @@ object ElevatorConstants {
val FOLLOWER_STATOR_CURRENT_LIMIT = 0.0.amps
val FOLLOWER_SUPPLY_CURRENT_LIMIT = 0.0.amps
val FOLLOWER_THRESHOLD_CURRENT_LIMIT = 0.0.amps

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,8 @@ import org.team4099.lib.units.base.grams
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.base.seconds
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.rotations
import org.team4099.lib.units.derived.volts
import org.team4099.lib.units.kilo
import org.team4099.lib.units.perMinute
import org.team4099.lib.units.perSecond

object FeederConstants {
Expand All @@ -27,8 +25,6 @@ object FeederConstants {

var WAIT_BEFORE_DETECT_VELOCITY_DROP = 1.seconds


val INTAKE_NOTE_VOLTAGE = 6.volts
val SHOOT_NOTE_VOLTAGE = 11.9.volts

}
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@ import org.team4099.lib.units.base.amps
import org.team4099.lib.units.derived.volts

object IntakeConstants {
val ROLLER_INERTIA = 0.002459315 // this one has been updated
val VOLTAGE_COMPENSATION = 12.0.volts
val ROLLER_INERTIA = 0.002459315 // this one has been updated
val VOLTAGE_COMPENSATION = 12.0.volts

// TODO: Change gear ratio according to robot
val ROLLER_CURRENT_LIMIT = 50.0.amps
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ import org.team4099.lib.units.derived.perInchSeconds
import org.team4099.lib.units.derived.volts
import org.team4099.lib.units.inInchesPerSecond
import org.team4099.lib.units.perSecond
import kotlin.time.Duration.Companion.seconds
import com.team4099.robot2023.subsystems.superstructure.Request.ElevatorRequest as ElevatorRequest

class Elevator(val io: ElevatorIO) : SubsystemBase() {
Expand All @@ -53,27 +52,26 @@ class Elevator(val io: ElevatorIO) : SubsystemBase() {
LoggedTunableValue(
"Elevator/kD", Pair({ it.inVoltsPerInchPerSecond }, { it.volts / 1.0.inches.perSecond })
)
private val kS =
LoggedTunableValue(
"Elevator/kS", Pair({ it.inVolts}, {it.volts})
)
private val kG =
LoggedTunableValue(
"Elevator/kG", Pair({ it.inVolts}, {it.volts})
)
private val kS = LoggedTunableValue("Elevator/kS", Pair({ it.inVolts }, { it.volts }))
private val kG = LoggedTunableValue("Elevator/kG", Pair({ it.inVolts }, { it.volts }))
private val kV =
LoggedTunableValue(
"Elevator/kG", Pair({it.inVoltsPerInchPerSecond}, {it.volts / 1.0.inches.perSecond})
"Elevator/kG", Pair({ it.inVoltsPerInchPerSecond }, { it.volts / 1.0.inches.perSecond })
)
private val kA =
LoggedTunableValue(
"Elevator/kA", Pair({it.inVoltsPerMeterPerSecondPerSecond}, {it.volts / 1.0.meters.perSecond.perSecond})
"Elevator/kA",
Pair(
{ it.inVoltsPerMeterPerSecondPerSecond },
{ it.volts / 1.0.meters.perSecond.perSecond }
)
)

object TunableElevatorHeights {
val enableElevator =
LoggedTunableNumber("Elevator/enableMovementElevator",
if (ElevatorConstants.ENABLE_ELEVATOR) 1.0 else 0.0)
LoggedTunableNumber(
"Elevator/enableMovementElevator", if (ElevatorConstants.ENABLE_ELEVATOR) 1.0 else 0.0
)

val minPosition =
LoggedTunableValue(
Expand All @@ -91,11 +89,15 @@ class Elevator(val io: ElevatorIO) : SubsystemBase() {
// TODO: change voltages
val openLoopExtendVoltage =
LoggedTunableValue(
"Elevator/openLoopExtendVoltage", ElevatorConstants.ELEVATOR_OPEN_LOOP_EXTEND_VOLTAGE, Pair({ it.inVolts }, { it.volts })
"Elevator/openLoopExtendVoltage",
ElevatorConstants.ELEVATOR_OPEN_LOOP_EXTEND_VOLTAGE,
Pair({ it.inVolts }, { it.volts })
)
val openLoopRetractVoltage =
LoggedTunableValue(
"Elevator/openLoopRetractVoltage", ElevatorConstants.ELEVATOR_OPEN_LOOP_RETRACT_VOLTAGE, Pair({ it.inVolts }, { it.volts })
"Elevator/openLoopRetractVoltage",
ElevatorConstants.ELEVATOR_OPEN_LOOP_RETRACT_VOLTAGE,
Pair({ it.inVolts }, { it.volts })
)

val shootSpeakerPosition =
Expand Down Expand Up @@ -190,7 +192,10 @@ class Elevator(val io: ElevatorIO) : SubsystemBase() {
get() =
currentRequest is ElevatorRequest.TargetingPosition &&
(
((inputs.elevatorPosition - elevatorPositionTarget).absoluteValue <= ElevatorConstants.ELEVATOR_SAFE_THRESHOLD) ||
(
(inputs.elevatorPosition - elevatorPositionTarget).absoluteValue <=
ElevatorConstants.ELEVATOR_SAFE_THRESHOLD
) ||
elevatorProfile.isFinished(Clock.fpgaTime - timeProfileGeneratedAt)
) &&
lastRequestedPosition == elevatorPositionTarget
Expand Down Expand Up @@ -222,8 +227,6 @@ class Elevator(val io: ElevatorIO) : SubsystemBase() {
ElevatorConstants.ELEVATOR_KV,
ElevatorConstants.ELEVATOR_KA
)


}

override fun periodic() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@ package com.team4099.robot2023.subsystems.elevator
import com.ctre.phoenix6.StatusSignal
import com.ctre.phoenix6.configs.Slot0Configs
import com.ctre.phoenix6.configs.TalonFXConfiguration
import com.ctre.phoenix6.controls.PositionDutyCycle
import com.ctre.phoenix6.controls.PositionVoltage
import com.ctre.phoenix6.hardware.TalonFX
import com.ctre.phoenix6.signals.NeutralModeValue
Expand All @@ -26,7 +25,6 @@ import org.team4099.lib.units.derived.IntegralGain
import org.team4099.lib.units.derived.ProportionalGain
import org.team4099.lib.units.derived.Volt
import org.team4099.lib.units.derived.inVolts
import org.team4099.lib.units.derived.rotations
import org.team4099.lib.units.derived.volts

object ElevatorIOKraken : ElevatorIO {
Expand Down Expand Up @@ -155,25 +153,21 @@ object ElevatorIOKraken : ElevatorIO {

override fun setOutputVoltage(voltage: ElectricalPotential) {
if (((leaderSensor.position < 0.5.inches) && (voltage < 0.volts)) ||
(leaderSensor.position > ElevatorConstants.ELEVATOR_MAX_EXTENSION - 0.5.inches && (voltage > 0.volts))) {
(
leaderSensor.position > ElevatorConstants.ELEVATOR_MAX_EXTENSION - 0.5.inches &&
(voltage > 0.volts)
)
) {
elevatorLeaderKraken.setVoltage(0.0)
}
else {
} else {
elevatorLeaderKraken.setVoltage(voltage.inVolts)
}
}

override fun setPosition(position: Length, feedForward: ElectricalPotential) {
elevatorLeaderKraken.setControl(
PositionVoltage(
leaderSensor.getRawPosition(),
0.0,
true,
feedForward.inVolts,
0,
false,
false,
false
leaderSensor.getRawPosition(), 0.0, true, feedForward.inVolts, 0, false, false, false
)
)
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ import org.team4099.lib.units.base.Meter
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.inPercentOutputPerSecond
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.derived.DerivativeGain
import org.team4099.lib.units.derived.ElectricalPotential
Expand Down Expand Up @@ -144,7 +143,10 @@ object ElevatorIONEO : ElevatorIO {
override fun setOutputVoltage(voltage: ElectricalPotential) {
// divide by 2 cause full power elevator is scary
if (((leaderSensor.position < 0.5.inches) && (voltage < 0.volts)) ||
(leaderSensor.position > ElevatorConstants.ELEVATOR_MAX_EXTENSION - 0.5.inches && (voltage > 0.volts))
(
leaderSensor.position > ElevatorConstants.ELEVATOR_MAX_EXTENSION - 0.5.inches &&
(voltage > 0.volts)
)
) {
leaderSparkMax.setVoltage(0.0)
} else {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.inKilograms
import org.team4099.lib.units.base.inMeters
import org.team4099.lib.units.base.inSeconds
import org.team4099.lib.units.base.inches
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.derived.DerivativeGain
import org.team4099.lib.units.derived.ElectricalPotential
Expand Down Expand Up @@ -99,15 +98,15 @@ object ElevatorIOSim : ElevatorIO {
*/
override fun setOutputVoltage(voltage: ElectricalPotential) {
Logger.recordOutput("Elevator/OutputTest", voltage)
val clampedVoltage =
clamp(
voltage,
-ElevatorConstants.VOLTAGE_COMPENSATION,
ElevatorConstants.VOLTAGE_COMPENSATION
)
lastAppliedVoltage = clampedVoltage

elevatorSim.setInputVoltage(clampedVoltage.inVolts)
val clampedVoltage =
clamp(
voltage,
-ElevatorConstants.VOLTAGE_COMPENSATION,
ElevatorConstants.VOLTAGE_COMPENSATION
)
lastAppliedVoltage = clampedVoltage

elevatorSim.setInputVoltage(clampedVoltage.inVolts)
}

/**
Expand All @@ -131,8 +130,7 @@ object ElevatorIOSim : ElevatorIO {
}

/** set the current encoder position to be the encoders zero value */
override fun zeroEncoder() {
}
override fun zeroEncoder() {}

/**
* updates the PID controller values using the sensor measurement for proportional intregral and
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class Feeder(val io: FeederIO) : SubsystemBase() {
FeederStates.OPEN_LOOP_INTAKE -> {
if (!hasNote) {
setFeederVoltage(feederTargetVoltage)
}
}
nextState = fromRequestToState(currentRequest)
}
FeederStates.OPEN_LOOP_SHOOT -> {
Expand Down Expand Up @@ -99,7 +99,6 @@ class Feeder(val io: FeederIO) : SubsystemBase() {
})
}


companion object {
enum class FeederStates {
UNINITIALIZED,
Expand All @@ -122,4 +121,3 @@ class Feeder(val io: FeederIO) : SubsystemBase() {
}
}
}

Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
package com.team4099.robot2023.subsystems.feeder

import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.inputs.LoggableInputs
import org.team4099.lib.units.base.amps
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@ import com.team4099.robot2023.config.constants.FeederConstants
import com.team4099.robot2023.subsystems.falconspin.MotorChecker
import com.team4099.robot2023.subsystems.falconspin.MotorCollection
import com.team4099.robot2023.subsystems.falconspin.Neo
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
Expand Down Expand Up @@ -64,7 +63,6 @@ object FeederIONeo : FeederIO {
inputs.feederSupplyCurrent =
inputs.feederStatorCurrent * feederSparkMax.appliedOutput.absoluteValue
inputs.feederTemp = feederSparkMax.motorTemperature.celsius

}

/**
Expand Down
Loading

0 comments on commit 8c154f7

Please sign in to comment.